56 remappings[
"image_raw"] = image_raw_topic;
57 remappings[
"image_mono"] = image_mono_topic;
58 remappings[
"image_color"] = image_color_topic;
60 manager.
load(debayer_name,
"image_proc/debayer", remappings, my_argv);
64 remappings[
"image_mono"] = image_mono_topic;
65 remappings[
"camera_info"] = camera_info_topic;
66 remappings[
"image_rect"] = image_rect_topic;
68 if (rectify_params.
valid())
70 manager.
load(rectify_mono_name,
"image_proc/rectify", remappings, my_argv);
74 remappings[
"image_mono"] = image_color_topic;
75 remappings[
"camera_info"] = camera_info_topic;
76 remappings[
"image_rect"] = image_rect_color_topic;
78 if (rectify_params.
valid())
80 manager.
load(rectify_color_name,
"image_proc/rectify", remappings, my_argv);
83 int main(
int argc,
char **argv)
85 ros::init(argc, argv,
"stereo_image_proc");
90 ROS_WARN(
"Remapping 'camera' has no effect! Start stereo_image_proc in the "
91 "stereo namespace instead.\nExample command-line usage:\n"
92 "\t$ ROS_NAMESPACE=%s rosrun stereo_image_proc stereo_image_proc",
97 ROS_WARN(
"Started in the global namespace! This is probably wrong. Start "
98 "stereo_image_proc in the stereo namespace.\nExample command-line usage:\n"
99 "\t$ ROS_NAMESPACE=my_stereo rosrun stereo_image_proc stereo_image_proc");
106 if (private_nh.
getParam(
"queue_size", queue_size))
107 shared_params[
"queue_size"] = queue_size;
109 int downsampling_factor;
110 if (private_nh.
getParam(
"downsampling_factor", downsampling_factor))
111 shared_params[
"downsampling_factor"] = downsampling_factor;
123 if (private_nh.
getParam(
"approximate_sync", approx_sync))
132 manager.
load(disparity_name,
"stereo_image_proc/disparity", remappings, my_argv);
138 if (shared_params.
valid())
140 manager.
load(point_cloud2_name,
"stereo_image_proc/point_cloud2", remappings, my_argv);
149 check_inputs.
start(topics, 60.0);