00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <ros/ros.h>
00036 #include <nodelet/loader.h>
00037 #include <image_proc/advertisement_checker.h>
00038
00039 void loadMonocularNodelets(nodelet::Loader& manager, const std::string& side,
00040 const XmlRpc::XmlRpcValue& rectify_params,
00041 const nodelet::V_string& my_argv)
00042 {
00043 nodelet::M_string remappings;
00044
00045
00046
00047
00048 std::string image_raw_topic = ros::names::resolve(side + "/image_raw");
00049 std::string image_mono_topic = ros::names::resolve(side + "/image_mono");
00050 std::string image_color_topic = ros::names::resolve(side + "/image_color");
00051 std::string image_rect_topic = ros::names::resolve(side + "/image_rect");
00052 std::string image_rect_color_topic = ros::names::resolve(side + "/image_rect_color");
00053 std::string camera_info_topic = ros::names::resolve(side + "/camera_info");
00054
00055
00056 remappings["image_raw"] = image_raw_topic;
00057 remappings["image_mono"] = image_mono_topic;
00058 remappings["image_color"] = image_color_topic;
00059 std::string debayer_name = ros::this_node::getName() + "_debayer_" + side;
00060 manager.load(debayer_name, "image_proc/debayer", remappings, my_argv);
00061
00062
00063 remappings.clear();
00064 remappings["image_mono"] = image_mono_topic;
00065 remappings["camera_info"] = camera_info_topic;
00066 remappings["image_rect"] = image_rect_topic;
00067 std::string rectify_mono_name = ros::this_node::getName() + "_rectify_mono_" + side;
00068 if (rectify_params.valid())
00069 ros::param::set(rectify_mono_name, rectify_params);
00070 manager.load(rectify_mono_name, "image_proc/rectify", remappings, my_argv);
00071
00072
00073 remappings.clear();
00074 remappings["image_mono"] = image_color_topic;
00075 remappings["camera_info"] = camera_info_topic;
00076 remappings["image_rect"] = image_rect_color_topic;
00077 std::string rectify_color_name = ros::this_node::getName() + "_rectify_color_" + side;
00078 if (rectify_params.valid())
00079 ros::param::set(rectify_color_name, rectify_params);
00080 manager.load(rectify_color_name, "image_proc/rectify", remappings, my_argv);
00081 }
00082
00083 int main(int argc, char **argv)
00084 {
00085 ros::init(argc, argv, "stereo_image_proc");
00086
00087
00088 if (ros::names::remap("camera") != "camera")
00089 {
00090 ROS_WARN("Remapping 'camera' has no effect! Start stereo_image_proc in the "
00091 "stereo namespace instead.\nExample command-line usage:\n"
00092 "\t$ ROS_NAMESPACE=%s rosrun stereo_image_proc stereo_image_proc",
00093 ros::names::remap("camera").c_str());
00094 }
00095 if (ros::this_node::getNamespace() == "/")
00096 {
00097 ROS_WARN("Started in the global namespace! This is probably wrong. Start "
00098 "stereo_image_proc in the stereo namespace.\nExample command-line usage:\n"
00099 "\t$ ROS_NAMESPACE=my_stereo rosrun stereo_image_proc stereo_image_proc");
00100 }
00101
00102
00103 ros::NodeHandle private_nh("~");
00104 XmlRpc::XmlRpcValue shared_params;
00105 int queue_size;
00106 if (private_nh.getParam("queue_size", queue_size))
00107 shared_params["queue_size"] = queue_size;
00108
00109 nodelet::Loader manager(false);
00110 nodelet::M_string remappings;
00111 nodelet::V_string my_argv;
00112 my_argv.push_back("--no-input-checks");
00113
00114
00115 loadMonocularNodelets(manager, "left", shared_params, my_argv);
00116 loadMonocularNodelets(manager, "right", shared_params, my_argv);
00117
00118
00119 bool approx_sync;
00120 if (private_nh.getParam("approximate_sync", approx_sync))
00121 shared_params["approximate_sync"] = XmlRpc::XmlRpcValue(approx_sync);
00122
00123
00124
00125
00126
00127
00128 std::string disparity_name = ros::this_node::getName();
00129 manager.load(disparity_name, "stereo_image_proc/disparity", remappings, my_argv);
00130
00131
00132
00133
00134 std::string point_cloud2_name = ros::this_node::getName() + "_point_cloud2";
00135 if (shared_params.valid())
00136 ros::param::set(point_cloud2_name, shared_params);
00137 manager.load(point_cloud2_name, "stereo_image_proc/point_cloud2", remappings, my_argv);
00138
00139
00140
00141
00142 std::string point_cloud_name = ros::this_node::getName() + "_point_cloud";
00143 if (shared_params.valid())
00144 ros::param::set(point_cloud_name, shared_params);
00145 manager.load(point_cloud_name, "stereo_image_proc/point_cloud", remappings, my_argv);
00146
00147
00148 ros::V_string topics;
00149 topics.push_back(ros::names::resolve("left/image_raw"));
00150 topics.push_back(ros::names::resolve("left/camera_info"));
00151 topics.push_back(ros::names::resolve("right/image_raw"));
00152 topics.push_back(ros::names::resolve("right/camera_info"));
00153 image_proc::AdvertisementChecker check_inputs(ros::NodeHandle(), ros::this_node::getName());
00154 check_inputs.start(topics, 60.0);
00155
00156 ros::spin();
00157 return 0;
00158 }