image_proc.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <ros/ros.h>
36 #include <nodelet/loader.h>
38 
39 int main(int argc, char **argv)
40 {
41  ros::init(argc, argv, "image_proc");
42 
43  // Check for common user errors
44  if (ros::names::remap("camera") != "camera")
45  {
46  ROS_WARN("Remapping 'camera' has no effect! Start image_proc in the "
47  "camera namespace instead.\nExample command-line usage:\n"
48  "\t$ ROS_NAMESPACE=%s rosrun image_proc image_proc",
49  ros::names::remap("camera").c_str());
50  }
51  if (ros::this_node::getNamespace() == "/")
52  {
53  ROS_WARN("Started in the global namespace! This is probably wrong. Start image_proc "
54  "in the camera namespace.\nExample command-line usage:\n"
55  "\t$ ROS_NAMESPACE=my_camera rosrun image_proc image_proc");
56  }
57 
58  // Shared parameters to be propagated to nodelet private namespaces
59  ros::NodeHandle private_nh("~");
60  XmlRpc::XmlRpcValue shared_params;
61  int queue_size;
62  if (private_nh.getParam("queue_size", queue_size))
63  shared_params["queue_size"] = queue_size;
64 
65  nodelet::Loader manager(false); // Don't bring up the manager ROS API
66  nodelet::M_string remappings;
67  nodelet::V_string my_argv;
68 
69  // Debayer nodelet, image_raw -> image_mono, image_color
70  std::string debayer_name = ros::this_node::getName() + "_debayer";
71  manager.load(debayer_name, "image_proc/debayer", remappings, my_argv);
72 
73  // Rectify nodelet, image_mono -> image_rect
74  std::string rectify_mono_name = ros::this_node::getName() + "_rectify_mono";
75  if (shared_params.valid())
76  ros::param::set(rectify_mono_name, shared_params);
77  manager.load(rectify_mono_name, "image_proc/rectify", remappings, my_argv);
78 
79  // Rectify nodelet, image_color -> image_rect_color
80  // NOTE: Explicitly resolve any global remappings here, so they don't get hidden.
81  remappings["image_mono"] = ros::names::resolve("image_color");
82  remappings["image_rect"] = ros::names::resolve("image_rect_color");
83  std::string rectify_color_name = ros::this_node::getName() + "_rectify_color";
84  if (shared_params.valid())
85  ros::param::set(rectify_color_name, shared_params);
86  manager.load(rectify_color_name, "image_proc/rectify", remappings, my_argv);
87 
88  // Check for only the original camera topics
89  ros::V_string topics;
90  topics.push_back(ros::names::resolve("image_raw"));
91  topics.push_back(ros::names::resolve("camera_info"));
93  check_inputs.start(topics, 60.0);
94 
95  ros::spin();
96  return 0;
97 }
nodelet::V_string
std::vector< std::string > V_string
ros::this_node::getNamespace
const ROSCPP_DECL std::string & getNamespace()
nodelet::M_string
std::map< std::string, std::string > M_string
loader.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
nodelet::Loader
nodelet::Loader::load
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
image_proc::AdvertisementChecker::start
void start(const ros::V_string &topics, double duration)
Definition: advertisement_checker.cpp:107
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
image_proc::AdvertisementChecker
Definition: advertisement_checker.h:73
ROS_WARN
#define ROS_WARN(...)
ros::names::remap
ROSCPP_DECL std::string remap(const std::string &name)
ros::param::set
ROSCPP_DECL void set(const std::string &key, bool b)
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
XmlRpc::XmlRpcValue::valid
bool valid() const
ros::spin
ROSCPP_DECL void spin()
main
int main(int argc, char **argv)
Definition: image_proc.cpp:39
ros::V_string
std::vector< std::string > V_string
advertisement_checker.h
XmlRpc::XmlRpcValue
ros::NodeHandle


image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:17