rectify.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 #include <boost/version.hpp>
35 #if ((BOOST_VERSION / 100) % 1000) >= 53
36 #include <boost/thread/lock_guard.hpp>
37 #endif
38 
39 #include <ros/ros.h>
40 #include <nodelet/nodelet.h>
43 #include <cv_bridge/cv_bridge.h>
44 #include <dynamic_reconfigure/server.h>
45 #include <image_proc/RectifyConfig.h>
46 
47 namespace image_proc {
48 
49 class RectifyNodelet : public nodelet::Nodelet
50 {
51  // ROS communication
54  int queue_size_;
55  std::string rectified_frame_suffix_;
56 
57  boost::mutex connect_mutex_;
59 
60  // Dynamic reconfigure
61  boost::recursive_mutex config_mutex_;
62  typedef image_proc::RectifyConfig Config;
63  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
66 
67  // Processing state (note: only safe because we're using single-threaded NodeHandle!)
69 
70  virtual void onInit();
71 
72  void connectCb();
73 
74  void imageCb(const sensor_msgs::ImageConstPtr& image_msg,
75  const sensor_msgs::CameraInfoConstPtr& info_msg);
76 
77  void configCb(Config &config, uint32_t level);
78 };
79 
81 {
83  ros::NodeHandle &private_nh = getPrivateNodeHandle();
84  it_.reset(new image_transport::ImageTransport(nh));
85 
86  // Read parameters
87  private_nh.param("queue_size", queue_size_, 5);
88  private_nh.param("rectified_frame_suffix", rectified_frame_suffix_, std::string(""));
89 
90  // Set up dynamic reconfigure
91  reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
92  ReconfigureServer::CallbackType f = boost::bind(&RectifyNodelet::configCb, this, boost::placeholders::_1, boost::placeholders::_2);
93  reconfigure_server_->setCallback(f);
94 
95  // Monitor whether anyone is subscribed to the output
97  // Make sure we don't enter connectCb() between advertising and assigning to pub_rect_
98  boost::lock_guard<boost::mutex> lock(connect_mutex_);
99  pub_rect_ = it_->advertise("image_rect", 1, connect_cb, connect_cb);
100 }
101 
102 // Handles (un)subscribing when clients (un)subscribe
104 {
105  boost::lock_guard<boost::mutex> lock(connect_mutex_);
106  if (pub_rect_.getNumSubscribers() == 0)
108  else if (!sub_camera_)
109  {
111  sub_camera_ = it_->subscribeCamera("image_mono", queue_size_, &RectifyNodelet::imageCb, this, hints);
112  }
113 }
114 
115 void RectifyNodelet::imageCb(const sensor_msgs::ImageConstPtr& image_msg,
116  const sensor_msgs::CameraInfoConstPtr& info_msg)
117 {
118  // Verify camera is actually calibrated
119  if (info_msg->K[0] == 0.0) {
120  NODELET_ERROR_THROTTLE(30, "Rectified topic '%s' requested but camera publishing '%s' "
121  "is uncalibrated", pub_rect_.getTopic().c_str(),
123  return;
124  }
125 
126  // If zero distortion, just pass the message along
127  bool zero_distortion = true;
128  for (size_t i = 0; i < info_msg->D.size(); ++i)
129  {
130  if (info_msg->D[i] != 0.0)
131  {
132  zero_distortion = false;
133  break;
134  }
135  }
136  // This will be true if D is empty/zero sized
137  if (zero_distortion)
138  {
139  pub_rect_.publish(image_msg);
140  return;
141  }
142 
143  // Update the camera model
144  model_.fromCameraInfo(info_msg);
145 
146  // Create cv::Mat views onto both buffers
147  const cv::Mat image = cv_bridge::toCvShare(image_msg)->image;
148  cv::Mat rect;
149 
150  // Rectify and publish
151  int interpolation;
152  {
153  boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
154  interpolation = config_.interpolation;
155  }
156  model_.rectifyImage(image, rect, interpolation);
157 
158  // Allocate new rectified image message
159  sensor_msgs::ImagePtr rect_msg = cv_bridge::CvImage(image_msg->header, image_msg->encoding, rect).toImageMsg();
160 
161  // If 'rectified_frame_suffix_' is not empty, add to header
162  if (!rectified_frame_suffix_.empty())
163  {
164  rect_msg->header.frame_id += rectified_frame_suffix_;
165  }
166 
167  pub_rect_.publish(rect_msg);
168 }
169 
170 void RectifyNodelet::configCb(Config &config, uint32_t level)
171 {
172  config_ = config;
173 }
174 
175 } // namespace image_proc
176 
177 // Register nodelet
image_proc::RectifyNodelet::config_mutex_
boost::recursive_mutex config_mutex_
Definition: rectify.cpp:125
image_transport::Publisher::getTopic
std::string getTopic() const
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_proc::RectifyNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: rectify.cpp:127
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
pinhole_camera_model.h
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
image_geometry::PinholeCameraModel::rectifyImage
void rectifyImage(const cv::Mat &raw, cv::Mat &rectified, int interpolation=cv::INTER_LINEAR) const
ros.h
image_proc::RectifyNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: rectify.cpp:116
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
image_proc::RectifyNodelet::imageCb
void imageCb(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: rectify.cpp:147
ros::TransportHints
image_proc::RectifyNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: rectify.cpp:128
image_proc::RectifyNodelet::pub_rect_
image_transport::Publisher pub_rect_
Definition: rectify.cpp:122
image_proc::RectifyNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: rectify.cpp:121
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
image_proc::RectifyNodelet::queue_size_
int queue_size_
Definition: rectify.cpp:118
f
f
image_proc::RectifyNodelet::onInit
virtual void onInit()
Definition: rectify.cpp:112
image_proc::RectifyNodelet
Definition: rectify.cpp:81
image_proc::RectifyNodelet::rectified_frame_suffix_
std::string rectified_frame_suffix_
Definition: rectify.cpp:119
image_geometry::PinholeCameraModel::fromCameraInfo
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
image_transport::CameraSubscriber
image_proc::RectifyNodelet::configCb
void configCb(Config &config, uint32_t level)
Definition: rectify.cpp:202
image_proc::RectifyNodelet::Config
image_proc::RectifyConfig Config
Definition: rectify.cpp:126
image_transport::CameraSubscriber::shutdown
void shutdown()
image_proc::RectifyNodelet::connectCb
void connectCb()
Definition: rectify.cpp:135
image_proc::RectifyNodelet::sub_camera_
image_transport::CameraSubscriber sub_camera_
Definition: rectify.cpp:117
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
image_transport.h
nodelet::Nodelet
image_proc
Definition: advertisement_checker.h:39
image_geometry::PinholeCameraModel
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
nodelet.h
image_transport::Publisher
cv_bridge.h
image_proc::RectifyNodelet::config_
Config config_
Definition: rectify.cpp:129
cv_bridge::CvImage
class_list_macros.hpp
image_proc::RectifyNodelet::model_
image_geometry::PinholeCameraModel model_
Definition: rectify.cpp:132
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
image_transport::CameraSubscriber::getInfoTopic
std::string getInfoTopic() const
image_transport::TransportHints
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ros::NodeHandle


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