36 #define BOOST_PARAMETER_MAX_ARITY 7 
   41 #include <opencv2/opencv.hpp> 
   49     DiagnosticNodelet::onInit();
 
   50     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
 
   51     pnh_->param(
"not_sync", 
not_sync_, 
false);
 
   53     pub_image_ = advertise<sensor_msgs::Image>(*pnh_, 
"output", 1);
 
   55       pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output/cloud", 1);
 
   77       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
   86         "input/camera_info", 1,
 
  107                         const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg)
 
  109     vital_checker_->poke();
 
  112       cv::Mat image = cv_ptr->image;
 
  113       cv::Rect roi(camera_info_msg->roi.x_offset, camera_info_msg->roi.y_offset,
 
  114                    camera_info_msg->roi.width, camera_info_msg->roi.height);
 
  116       cv::Mat image_roi = image(roi);
 
  132     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
 
  139     const sensor_msgs::Image::ConstPtr& image_msg)
 
  148     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
 
  151     vital_checker_->poke();
 
  156       pcl::PointCloud<pcl::PointXYZRGB>::Ptr 
cloud 
  157         (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  159       pcl::PointCloud<pcl::PointXYZRGB>::Ptr clipped_cloud
 
  160         (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
  161       cv::Rect region = 
model.rectifiedRoi();
 
  162       pcl::PointXYZRGB nan_point;
 
  163       nan_point.x = nan_point.y = nan_point.z
 
  164         = std::numeric_limits<float>::quiet_NaN();;
 
  165       for (
size_t i = 0; 
i < 
cloud->points.size(); 
i++) {
 
  166         pcl::PointXYZRGB 
p = 
cloud->points[
i];
 
  168         if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
 
  169           cv::Point2d uv = 
model.project3dToPixel(cv::Point3d(
p.x, 
p.y, 
p.z));
 
  170           if (uv.x >= 0 && uv.x <= region.width &&
 
  171               uv.y >= 0 && uv.y <= region.height) {
 
  172             indices.indices.push_back(
i);
 
  173             clipped_cloud->points.push_back(
p);
 
  178           clipped_cloud->points.push_back(nan_point);
 
  182         clipped_cloud->width = 
cloud->width;
 
  183         clipped_cloud->height = 
cloud->height;
 
  185       sensor_msgs::PointCloud2 ros_cloud;
 
  187       ros_cloud.header = cloud_msg->header;
 
  189       indices.header = cloud_msg->header;