void objectDetect::run() { std::string config_topic("/config"); config_topic += ros::this_node::getNamespace() + "/dpm"; config_sub_ = nh_.subscribe<runtime_manager::ConfigCarDpm>(config_topic, 1, &objectDetect::configCallback, this); img_sub_ = nh_.subscribe<sensor_msgs::Image>(image_topic_name, 1, &objectDetect::imageCallback, this); detect_pub_ = nh_.advertise<cv_tracker::image_obj>("image_obj", 1); }
int kf_main(int argc, char* argv[]) { ros::init(argc, argv, "kf"); ros::NodeHandle n; ros::NodeHandle private_nh("~"); image_objects = n.advertise<cv_tracker::image_obj_tracked>("image_obj_tracked", 1); cv::generateColors(_colors, 25); std::string image_topic; std::string obj_topic; if (private_nh.getParam("image_node", image_topic)) { ROS_INFO("Setting image node to %s", image_topic.c_str()); } else { ROS_INFO("No image node received, defaulting to image_raw, you can use _image_node:=YOUR_TOPIC"); image_topic = "/image_raw"; } if (private_nh.getParam("object_node", image_topic)) { ROS_INFO("Setting object node to %s", image_topic.c_str()); } else { ROS_INFO("No object node received, defaulting to image_obj_ranged, you can use _object_node:=YOUR_TOPIC"); obj_topic = "image_obj_ranged"; } init_params(); ros::Subscriber sub_image = n.subscribe(image_topic, 1, image_callback); ros::Subscriber sub_dpm = n.subscribe(obj_topic, 1, detections_callback); std::string config_topic("/config"); config_topic += ros::this_node::getNamespace() + "/kf"; ros::Subscriber config_subscriber = n.subscribe(config_topic, 1, kf_config_cb); //TimeSynchronizer<Image, dpm::ImageObjects> sync(image_sub, pos_sub, 10); //sync.registerCallback(boost::bind(&sync_callback, _1, _2)); track_ready_ = false; detect_ready_ = false; ros::spin(); return 0; }
int main(int argc, char **argv) { init(); ros::init(argc, argv, "range_fusion"); ros::NodeHandle n; ros::NodeHandle private_nh("~"); std::string image_topic; std::string points_topic; if (private_nh.getParam("image_node", image_topic)) { ROS_INFO("Setting image node to %s", image_topic.c_str()); } else { ROS_INFO("No image node received, defaulting to image_obj, you can use _image_node:=YOUR_TOPIC"); image_topic = "image_obj"; } if (private_nh.getParam("points_node", points_topic)) { ROS_INFO("Setting points node to %s", points_topic.c_str()); } else { ROS_INFO("No points node received, defaulting to vscan_image, you can use _points_node:=YOUR_TOPIC"); points_topic = "/vscan_image"; } // ros::Subscriber image_obj_sub = n.subscribe("/obj_car/image_obj", 1, DetectedObjectsCallback); ros::Subscriber image_obj_sub = n.subscribe(image_topic, 1, DetectedObjectsCallback); //ros::Subscriber scan_image_sub = n.subscribe("scan_image", 1, ScanImageCallback); ros::Subscriber points_image_sub =n.subscribe(points_topic, 1, PointsImageCallback); #if _DEBUG ros::Subscriber image_sub = n.subscribe(IMAGE_TOPIC, 1, IMAGE_CALLBACK); #endif fused_objects = n.advertise<autoware_msgs::ImageObjRanged>("image_obj_ranged", 1); ros::Subscriber config_subscriber; std::string config_topic("/config"); config_topic += ros::this_node::getNamespace() + "/fusion"; config_subscriber = n.subscribe(config_topic, 1, config_cb); ros::spin(); destroy(); return 0; }
void Run() { std::string image_raw_topic_str; std::string image_obj_topic_str; ros::NodeHandle private_node_handle("~");//to receive args if (private_node_handle.getParam("image_raw_node", image_raw_topic_str)) { ROS_INFO("Setting image node to %s", image_raw_topic_str.c_str()); } else { ROS_INFO("No image node received, defaulting to /image_raw, you can use _image_raw_node:=YOUR_TOPIC"); image_raw_topic_str = "/image_raw"; } if (private_node_handle.getParam(ros::this_node::getNamespace() + "/img_obj_node", image_obj_topic_str)) { ROS_INFO("Setting object node to %s", image_obj_topic_str.c_str()); } else { ROS_INFO("No object node received, defaulting to image_obj_ranged, you can use _img_obj_node:=YOUR_TOPIC"); image_obj_topic_str = "image_obj_ranged"; } publisher_tracked_objects_ = node_handle_.advertise<cv_tracker_msgs::image_obj_tracked>("image_obj_tracked", 1); ROS_INFO("Subscribing to... %s", image_raw_topic_str.c_str()); ROS_INFO("Subscribing to... %s", image_obj_topic_str.c_str()); subscriber_image_raw_ = node_handle_.subscribe(image_raw_topic_str, 1, &RosTrackerApp::image_callback, this); subscriber_image_obj_ = node_handle_.subscribe(image_obj_topic_str, 1, &RosTrackerApp::detections_callback, this); std::string config_topic("/config"); config_topic += ros::this_node::getNamespace() + "/klt"; //node_handle.subscribe(config_topic, 1, &RosTrackerApp::klt_config_cb, this); ros::spin(); ROS_INFO("END klt"); }
void Run() { //ROS STUFF ros::NodeHandle private_node_handle("~");//to receive args //RECEIVE IMAGE TOPIC NAME std::string image_raw_topic_str; if (private_node_handle.getParam("image_raw_node", image_raw_topic_str)) { ROS_INFO("Setting image node to %s", image_raw_topic_str.c_str()); } else { ROS_INFO("No image node received, defaulting to /image_raw, you can use _image_raw_node:=YOUR_TOPIC"); image_raw_topic_str = "/image_raw"; } std::string network_definition_file; std::string pretrained_model_file; if (private_node_handle.getParam("network_definition_file", network_definition_file)) { ROS_INFO("Network Definition File (Config): %s", network_definition_file.c_str()); } else { ROS_INFO("No Network Definition File was received. Finishing execution."); return; } if (private_node_handle.getParam("pretrained_model_file", pretrained_model_file)) { ROS_INFO("Pretrained Model File (Weights): %s", pretrained_model_file.c_str()); } else { ROS_INFO("No Pretrained Model File was received. Finishing execution."); return; } if (private_node_handle.getParam("score_threshold", score_threshold_)) { ROS_INFO("Score Threshold: %f", score_threshold_); } if (private_node_handle.getParam("nms_threshold", nms_threshold_)) { ROS_INFO("NMS Threshold: %f", nms_threshold_); } ROS_INFO("Initializing Yolo2 on Darknet..."); yolo_detector_.load(network_definition_file, pretrained_model_file, score_threshold_, nms_threshold_); ROS_INFO("Initialization complete."); publisher_car_objects_ = node_handle_.advertise<autoware_msgs::image_obj>("/obj_car/image_obj", 1); publisher_person_objects_ = node_handle_.advertise<autoware_msgs::image_obj>("/obj_person/image_obj", 1); ROS_INFO("Subscribing to... %s", image_raw_topic_str.c_str()); subscriber_image_raw_ = node_handle_.subscribe(image_raw_topic_str, 1, &Yolo2DetectorNode::image_callback, this); std::string config_topic("/config"); config_topic += "/yolo2"; subscriber_yolo_config_ = node_handle_.subscribe(config_topic, 1, &Yolo2DetectorNode::config_cb, this); ros::spin(); ROS_INFO("END Yolo2"); }
void Run() { //ROS STUFF ros::NodeHandle private_node_handle("~");//to receive args //RECEIVE IMAGE TOPIC NAME std::string image_raw_topic_str; if (private_node_handle.getParam("image_raw_node", image_raw_topic_str)) { ROS_INFO("Setting image node to %s", image_raw_topic_str.c_str()); } else { ROS_INFO("No image node received, defaulting to /image_raw, you can use _image_raw_node:=YOUR_TOPIC"); image_raw_topic_str = "/image_raw"; } //RECEIVE CONVNET FILENAMES std::string network_definition_file; std::string pretrained_model_file; if (private_node_handle.getParam("network_definition_file", network_definition_file)) { ROS_INFO("Network Definition File: %s", network_definition_file.c_str()); } else { ROS_INFO("No Network Definition File was received. Finishing execution."); return; } if (private_node_handle.getParam("pretrained_model_file", pretrained_model_file)) { ROS_INFO("Pretrained Model File: %s", pretrained_model_file.c_str()); } else { ROS_INFO("No Pretrained Model File was received. Finishing execution."); return; } if (private_node_handle.getParam("use_gpu", use_gpu_)) { ROS_INFO("GPU Mode: %d", use_gpu_); } int gpu_id; if (private_node_handle.getParam("gpu_device_id", gpu_id )) { ROS_INFO("GPU Device ID: %d", gpu_id); gpu_device_id_ = (unsigned int) gpu_id; } detect_classes_.push_back(Rcnn::CAR); detect_classes_.push_back(Rcnn::PERSON); detect_classes_.push_back(Rcnn::BUS); //RCNN STUFF rcnn_detector_ = new RcnnDetector(network_definition_file, pretrained_model_file, use_gpu_, gpu_device_id_); if (NULL == rcnn_detector_) { ROS_INFO("Error while creating RCNN Object"); return; } publisher_car_objects_ = node_handle_.advertise<cv_tracker::image_obj>("/obj_car/image_obj", 1); publisher_person_objects_ = node_handle_.advertise<cv_tracker::image_obj>("/obj_person/image_obj", 1); ROS_INFO("Subscribing to... %s", image_raw_topic_str.c_str()); subscriber_image_raw_ = node_handle_.subscribe(image_raw_topic_str, 1, &RosRcnnApp::image_callback, this); std::string config_topic("/config"); config_topic += ros::this_node::getNamespace() + "/rcnn"; subscriber_rcnn_config_ =node_handle_.subscribe(config_topic, 1, &RosRcnnApp::config_cb, this); ros::spin(); ROS_INFO("END rcnn"); }
int main(int argc, char* argv[]) { ros::init(argc, argv, "dpm_ttic"); ros::NodeHandle n; ros::NodeHandle private_nh("~"); if (!private_nh.getParam("image_raw_topic", image_topic_name)) { image_topic_name = "/image_raw"; } if (!private_nh.getParam("detection_class_name", object_class)) { object_class = "car"; } std::string comp_csv_path; if (!private_nh.getParam("comp_model_path", comp_csv_path)) { comp_csv_path = STR(MODEL_DIR) "car_comp.csv"; } std::string root_csv_path; if (!private_nh.getParam("root_model_path", root_csv_path)) { root_csv_path = STR(MODEL_DIR) "car_root.csv"; } std::string part_csv_path; if (!private_nh.getParam("part_model_path", part_csv_path)) { part_csv_path = STR(MODEL_DIR) "car_part.csv"; } #if defined(HAS_GPU) if (!private_nh.getParam("use_gpu", use_gpu)) { use_gpu = false; } std::string cubin = get_cubin_path(n, STR(DEFAULT_CUBIN)); if (use_gpu) { dpm_ttic_gpu_init_cuda(cubin); } #endif set_default_param(ttic_param); const char *com_csv = comp_csv_path.c_str(); const char *root_csv = root_csv_path.c_str(); const char *part_csv = part_csv_path.c_str(); #if defined(HAS_GPU) if (use_gpu) { gpu_model = new DPMTTICGPU(com_csv, root_csv, part_csv); } else { #endif ttic_model = new DPMTTIC(com_csv, root_csv, part_csv); #if defined(HAS_GPU) } #endif ros::Subscriber sub = n.subscribe(image_topic_name, 1, image_raw_cb); image_obj_pub = n.advertise<cv_tracker::image_obj>("image_obj", 1); ros::Subscriber config_sub; std::string config_topic("/config"); config_topic += ros::this_node::getNamespace() + "/dpm"; config_sub = n.subscribe(config_topic, 1, config_cb); ros::spin(); #if defined(HAS_GPU) if (use_gpu) { dpm_ttic_gpu_cleanup_cuda(); delete gpu_model; } else { #endif delete ttic_model; #if defined(HAS_GPU) } #endif return 0; }