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 int main(int argc, char **argv)
00040 {
00041 ros::init(argc, argv, "image_proc");
00042
00043
00044 if (ros::names::remap("camera") != "camera")
00045 {
00046 ROS_WARN("Remapping 'camera' has no effect! Start image_proc in the "
00047 "camera namespace instead.\nExample command-line usage:\n"
00048 "\t$ ROS_NAMESPACE=%s rosrun image_proc image_proc",
00049 ros::names::remap("camera").c_str());
00050 }
00051 if (ros::this_node::getNamespace() == "/")
00052 {
00053 ROS_WARN("Started in the global namespace! This is probably wrong. Start image_proc "
00054 "in the camera namespace.\nExample command-line usage:\n"
00055 "\t$ ROS_NAMESPACE=my_camera rosrun image_proc image_proc");
00056 }
00057
00058
00059 ros::NodeHandle private_nh("~");
00060 XmlRpc::XmlRpcValue shared_params;
00061 int queue_size;
00062 if (private_nh.getParam("queue_size", queue_size))
00063 shared_params["queue_size"] = queue_size;
00064
00065 nodelet::Loader manager(false);
00066 nodelet::M_string remappings;
00067 nodelet::V_string my_argv;
00068 my_argv.push_back("--no-input-checks");
00069
00070
00071 std::string debayer_name = ros::this_node::getName() + "_debayer";
00072 manager.load(debayer_name, "image_proc/debayer", remappings, my_argv);
00073
00074
00075 std::string rectify_mono_name = ros::this_node::getName() + "_rectify_mono";
00076 if (shared_params.valid())
00077 ros::param::set(rectify_mono_name, shared_params);
00078 manager.load(rectify_mono_name, "image_proc/rectify", remappings, my_argv);
00079
00080
00081
00082 remappings["image_mono"] = ros::names::resolve("image_color");
00083 remappings["image_rect"] = ros::names::resolve("image_rect_color");
00084 std::string rectify_color_name = ros::this_node::getName() + "_rectify_color";
00085 if (shared_params.valid())
00086 ros::param::set(rectify_color_name, shared_params);
00087 manager.load(rectify_color_name, "image_proc/rectify", remappings, my_argv);
00088
00089
00090 ros::V_string topics;
00091 topics.push_back("image_raw");
00092 topics.push_back("camera_info");
00093 image_proc::AdvertisementChecker check_inputs(ros::NodeHandle(), ros::this_node::getName());
00094 check_inputs.start(topics, 60.0);
00095
00096 ros::spin();
00097 return 0;
00098 }