Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037
00038 #include "jsk_pcl_ros/roi_clipper.h"
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <opencv2/opencv.hpp>
00042 #include <image_geometry/pinhole_camera_model.h>
00043 #include "jsk_pcl_ros/pcl_conversion_util.h"
00044
00045 namespace jsk_pcl_ros
00046 {
00047 void ROIClipper::onInit()
00048 {
00049 DiagnosticNodelet::onInit();
00050 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00051 pnh_->param("not_sync", not_sync_, false);
00052 pnh_->param("keep_organized", keep_organized_, false);
00053 pub_image_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00054 if (not_sync_) {
00055 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
00056 pub_cloud_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/cloud_indices", 1);
00057 }
00058 }
00059
00060 void ROIClipper::subscribe()
00061 {
00062 if (!not_sync_) {
00063 sub_image_.subscribe(*pnh_, "input/image", 1);
00064 sub_info_.subscribe(*pnh_, "input/camera_info", 1);
00065 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00066 sync_->connectInput(sub_image_, sub_info_);
00067 sync_->registerCallback(boost::bind(&ROIClipper::clip, this, _1, _2));
00068 }
00069 else {
00070 sub_image_no_sync_ = pnh_->subscribe(
00071 "input/image", 1,
00072 &ROIClipper::imageCallback, this);
00073 sub_info_no_sync_ = pnh_->subscribe(
00074 "input/camera_info", 1,
00075 &ROIClipper::infoCallback, this);
00076 sub_cloud_no_sync_ = pnh_->subscribe(
00077 "input/cloud", 1,
00078 &ROIClipper::cloudCallback, this);
00079 }
00080 }
00081
00082 void ROIClipper::unsubscribe()
00083 {
00084 if (!not_sync_) {
00085 sub_image_.unsubscribe();
00086 sub_info_.unsubscribe();
00087 }
00088 else {
00089 sub_image_no_sync_.shutdown();
00090 sub_info_no_sync_.shutdown();
00091 sub_cloud_no_sync_.shutdown();
00092 }
00093 }
00094 void ROIClipper::clip(const sensor_msgs::Image::ConstPtr& image_msg,
00095 const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg)
00096 {
00097 vital_checker_->poke();
00098 try {
00099 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::RGB8);
00100 cv::Mat image = cv_ptr->image;
00101 cv::Rect roi(camera_info_msg->roi.x_offset, camera_info_msg->roi.y_offset,
00102 camera_info_msg->roi.width, camera_info_msg->roi.height);
00103
00104 cv::Mat image_roi = image(roi);
00105
00106
00107 cv_bridge::CvImage roi_bridge(image_msg->header,
00108 sensor_msgs::image_encodings::RGB8,
00109 image_roi);
00110 pub_image_.publish(roi_bridge.toImageMsg());
00111 }
00112 catch (cv_bridge::Exception& e)
00113 {
00114 JSK_NODELET_ERROR("cv_bridge exception: %s", e.what());
00115 return;
00116 }
00117 }
00118
00119 void ROIClipper::infoCallback(
00120 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00121 {
00122 boost::mutex::scoped_lock lock(mutex_);
00123 latest_camera_info_ = info_msg;
00124 }
00125
00126 void ROIClipper::imageCallback(
00127 const sensor_msgs::Image::ConstPtr& image_msg)
00128 {
00129 boost::mutex::scoped_lock lock(mutex_);
00130 if (latest_camera_info_) {
00131 clip(image_msg, latest_camera_info_);
00132 }
00133 }
00134
00135 void ROIClipper::cloudCallback(
00136 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00137 {
00138 boost::mutex::scoped_lock lock(mutex_);
00139 vital_checker_->poke();
00140 if (latest_camera_info_) {
00141 image_geometry::PinholeCameraModel model;
00142 PCLIndicesMsg indices;
00143 model.fromCameraInfo(latest_camera_info_);
00144 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud
00145 (new pcl::PointCloud<pcl::PointXYZRGB>);
00146 pcl::fromROSMsg(*cloud_msg, *cloud);
00147 pcl::PointCloud<pcl::PointXYZRGB>::Ptr clipped_cloud
00148 (new pcl::PointCloud<pcl::PointXYZRGB>);
00149 cv::Rect region = model.rectifiedRoi();
00150 pcl::PointXYZRGB nan_point;
00151 nan_point.x = nan_point.y = nan_point.z
00152 = std::numeric_limits<float>::quiet_NaN();;
00153 for (size_t i = 0; i < cloud->points.size(); i++) {
00154 pcl::PointXYZRGB p = cloud->points[i];
00155 bool foundp = false;
00156 if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00157 cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00158 if (uv.x >= 0 && uv.x <= region.width &&
00159 uv.y >= 0 && uv.y <= region.height) {
00160 indices.indices.push_back(i);
00161 clipped_cloud->points.push_back(p);
00162 foundp = true;
00163 }
00164 }
00165 if (!foundp && keep_organized_) {
00166 clipped_cloud->points.push_back(nan_point);
00167 }
00168 }
00169 if (keep_organized_) {
00170 clipped_cloud->width = cloud->width;
00171 clipped_cloud->height = cloud->height;
00172 }
00173 sensor_msgs::PointCloud2 ros_cloud;
00174 pcl::toROSMsg(*clipped_cloud, ros_cloud);
00175 ros_cloud.header = cloud_msg->header;
00176 pub_cloud_.publish(ros_cloud);
00177 indices.header = cloud_msg->header;
00178 pub_cloud_indices_.publish(indices);
00179 }
00180 }
00181
00182 void ROIClipper::updateDiagnostic(
00183 diagnostic_updater::DiagnosticStatusWrapper &stat)
00184 {
00185 if (vital_checker_->isAlive()) {
00186 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00187 "ROIClipper running");
00188 }
00189 else {
00190 jsk_topic_tools::addDiagnosticErrorSummary(
00191 "ROIClipper", vital_checker_, stat);
00192 }
00193
00194 }
00195 }
00196
00197 #include <pluginlib/class_list_macros.h>
00198 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ROIClipper, nodelet::Nodelet);