rectify.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <image_geometry/pinhole_camera_model.h>
00005 #include <cv_bridge/cv_bridge.h>
00006 #include <dynamic_reconfigure/server.h>
00007 #include <image_proc/RectifyConfig.h>
00008 
00009 namespace image_proc {
00010 
00011 class RectifyNodelet : public nodelet::Nodelet
00012 {
00013   // ROS communication
00014   boost::shared_ptr<image_transport::ImageTransport> it_;
00015   image_transport::CameraSubscriber sub_camera_;
00016   int queue_size_;
00017   
00018   boost::mutex connect_mutex_;
00019   image_transport::Publisher pub_rect_;
00020 
00021   // Dynamic reconfigure
00022   boost::recursive_mutex config_mutex_;
00023   typedef image_proc::RectifyConfig Config;
00024   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00025   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00026   Config config_;
00027 
00028   // Processing state (note: only safe because we're using single-threaded NodeHandle!)
00029   image_geometry::PinholeCameraModel model_;
00030 
00031   virtual void onInit();
00032 
00033   void connectCb();
00034 
00035   void imageCb(const sensor_msgs::ImageConstPtr& image_msg,
00036                const sensor_msgs::CameraInfoConstPtr& info_msg);
00037 
00038   void configCb(Config &config, uint32_t level);
00039 };
00040 
00041 void RectifyNodelet::onInit()
00042 {
00043   ros::NodeHandle &nh         = getNodeHandle();
00044   ros::NodeHandle &private_nh = getPrivateNodeHandle();
00045   it_.reset(new image_transport::ImageTransport(nh));
00046 
00047   // Read parameters
00048   private_nh.param("queue_size", queue_size_, 5);
00049 
00050   // Set up dynamic reconfigure
00051   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
00052   ReconfigureServer::CallbackType f = boost::bind(&RectifyNodelet::configCb, this, _1, _2);
00053   reconfigure_server_->setCallback(f);
00054 
00055   // Monitor whether anyone is subscribed to the output
00056   image_transport::SubscriberStatusCallback connect_cb = boost::bind(&RectifyNodelet::connectCb, this);
00057   // Make sure we don't enter connectCb() between advertising and assigning to pub_rect_
00058   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00059   pub_rect_  = it_->advertise("image_rect",  1, connect_cb, connect_cb);
00060 }
00061 
00062 // Handles (un)subscribing when clients (un)subscribe
00063 void RectifyNodelet::connectCb()
00064 {
00065   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00066   if (pub_rect_.getNumSubscribers() == 0)
00067     sub_camera_.shutdown();
00068   else if (!sub_camera_)
00069   {
00070     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00071     sub_camera_ = it_->subscribeCamera("image_mono", queue_size_, &RectifyNodelet::imageCb, this, hints);
00072   }
00073 }
00074 
00075 void RectifyNodelet::imageCb(const sensor_msgs::ImageConstPtr& image_msg,
00076                              const sensor_msgs::CameraInfoConstPtr& info_msg)
00077 {
00078   // Verify camera is actually calibrated
00079   if (info_msg->K[0] == 0.0) {
00080     NODELET_ERROR_THROTTLE(30, "Rectified topic '%s' requested but camera publishing '%s' "
00081                            "is uncalibrated", pub_rect_.getTopic().c_str(),
00082                            sub_camera_.getInfoTopic().c_str());
00083     return;
00084   }
00085 
00086   // If zero distortion, just pass the message along
00087   if (info_msg->D.empty() || info_msg->D[0] == 0.0)
00088   {
00089     pub_rect_.publish(image_msg);
00090     return;
00091   }
00092 
00093   // Update the camera model
00094   model_.fromCameraInfo(info_msg);
00095   
00096   // Create cv::Mat views onto both buffers
00097   const cv::Mat image = cv_bridge::toCvShare(image_msg)->image;
00098   cv::Mat rect;
00099 
00100   // Rectify and publish
00101   int interpolation;
00102   {
00103     boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
00104     interpolation = config_.interpolation;
00105   }
00106   model_.rectifyImage(image, rect, interpolation);
00107 
00108   // Allocate new rectified image message
00109   sensor_msgs::ImagePtr rect_msg = cv_bridge::CvImage(image_msg->header, image_msg->encoding, rect).toImageMsg();
00110   pub_rect_.publish(rect_msg);
00111 }
00112 
00113 void RectifyNodelet::configCb(Config &config, uint32_t level)
00114 {
00115   config_ = config;
00116 }
00117 
00118 } // namespace image_proc
00119 
00120 // Register nodelet
00121 #include <pluginlib/class_list_macros.h>
00122 PLUGINLIB_DECLARE_CLASS(image_proc, rectify, image_proc::RectifyNodelet, nodelet::Nodelet)


image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Fri Jan 3 2014 11:24:35