34 #include <boost/version.hpp> 
   35 #if ((BOOST_VERSION / 100) % 1000) >= 53 
   36 #include <boost/thread/lock_guard.hpp> 
   44 #include <dynamic_reconfigure/server.h> 
   45 #include <image_proc/RectifyConfig.h> 
   62   typedef image_proc::RectifyConfig 
Config;
 
   74   void imageCb(
const sensor_msgs::ImageConstPtr& image_msg,
 
   75                const sensor_msgs::CameraInfoConstPtr& info_msg);
 
   92   ReconfigureServer::CallbackType 
f = boost::bind(&
RectifyNodelet::configCb, 
this, boost::placeholders::_1, boost::placeholders::_2);
 
   99   pub_rect_  = 
it_->advertise(
"image_rect",  1, connect_cb, connect_cb);
 
  116                              const sensor_msgs::CameraInfoConstPtr& info_msg)
 
  119   if (info_msg->K[0] == 0.0) {
 
  127   bool zero_distortion = 
true;
 
  128   for (
size_t i = 0; i < info_msg->D.size(); ++i)
 
  130     if (info_msg->D[i] != 0.0)
 
  132       zero_distortion = 
false;
 
  153     boost::lock_guard<boost::recursive_mutex> lock(
config_mutex_);
 
  154     interpolation = 
config_.interpolation;