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 #include "jsk_recognition_utils/pcl_conversion_util.h"
00038 #include <pcl/range_image/range_image_planar.h>
00039 #include <pcl/range_image/range_image_spherical.h>
00040 #include "jsk_pcl_ros/border_estimator.h"
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <sensor_msgs/image_encodings.h>
00043
00044 namespace jsk_pcl_ros
00045 {
00046 void BorderEstimator::onInit()
00047 {
00048 ConnectionBasedNodelet::onInit();
00049
00050 pnh_->param("model_type", model_type_, std::string("planar"));
00051 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00052 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00053 boost::bind (&BorderEstimator::configCallback, this, _1, _2);
00054 srv_->setCallback (f);
00055
00056 pub_border_ = advertise<PCLIndicesMsg>(*pnh_, "output_border_indices", 1);
00057 pub_veil_ = advertise<PCLIndicesMsg>(*pnh_, "output_veil_indices", 1);
00058 pub_shadow_ = advertise<PCLIndicesMsg>(*pnh_, "output_shadow_indices", 1);
00059 pub_range_image_ = advertise<sensor_msgs::Image>(
00060 *pnh_, "output_range_image", 1);
00061 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
00062 *pnh_, "output_cloud", 1);
00063
00064 onInitPostProcess();
00065 }
00066
00067 void BorderEstimator::subscribe()
00068 {
00069 if (model_type_ == "planar") {
00070 sub_point_.subscribe(*pnh_, "input", 1);
00071 sub_camera_info_.subscribe(*pnh_, "input_camera_info", 1);
00072 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00073 sync_->connectInput(sub_point_, sub_camera_info_);
00074 sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, _1, _2));
00075 }
00076 else if (model_type_ == "laser") {
00077 sub_ = pnh_->subscribe("input", 1, &BorderEstimator::estimate, this);
00078 }
00079 }
00080
00081 void BorderEstimator::unsubscribe()
00082 {
00083 if (model_type_ == "planar") {
00084 sub_point_.unsubscribe();
00085 sub_camera_info_.unsubscribe();
00086 }
00087 else if (model_type_ == "laser") {
00088 sub_.shutdown();
00089 }
00090 }
00091
00092 void BorderEstimator::publishCloud(
00093 ros::Publisher& pub,
00094 const pcl::PointIndices& inlier,
00095 const std_msgs::Header& header)
00096 {
00097 PCLIndicesMsg msg;
00098 msg.header = header;
00099 msg.indices = inlier.indices;
00100 pub.publish(msg);
00101 }
00102
00103 void BorderEstimator::estimate(
00104 const sensor_msgs::PointCloud2::ConstPtr& msg)
00105 {
00106 boost::mutex::scoped_lock lock(mutex_);
00107 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00108 pcl::fromROSMsg(*msg, *cloud);
00109 pcl::RangeImage range_image;
00110 if (model_type_ == "sphere") {
00111 range_image = pcl::RangeImageSpherical();
00112 }
00113 range_image.createFromPointCloud(
00114 *cloud,
00115 angular_resolution_,
00116 max_angle_width_, max_angle_height_,
00117 Eigen::Affine3f::Identity(),
00118 pcl::RangeImage::CAMERA_FRAME,
00119 noise_level_,
00120 min_range_,
00121 border_size_);
00122 range_image.setUnseenToMaxRange();
00123 computeBorder(range_image, msg->header);
00124 }
00125
00126 void BorderEstimator::computeBorder(
00127 const pcl::RangeImage& range_image,
00128 const std_msgs::Header& header)
00129 {
00130 pcl::RangeImageBorderExtractor border_extractor (&range_image);
00131 pcl::PointCloud<pcl::BorderDescription> border_descriptions;
00132 border_extractor.compute (border_descriptions);
00133 pcl::PointIndices border_indices, veil_indices, shadow_indices;
00134 for (int y = 0; y < (int)range_image.height; ++y) {
00135 for (int x = 0; x < (int)range_image.width; ++x) {
00136 if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__OBSTACLE_BORDER]) {
00137 border_indices.indices.push_back (y*range_image.width + x);
00138 }
00139 if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__VEIL_POINT]) {
00140 veil_indices.indices.push_back (y*range_image.width + x);
00141 }
00142 if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__SHADOW_BORDER]) {
00143 shadow_indices.indices.push_back (y*range_image.width + x);
00144 }
00145 }
00146 }
00147 publishCloud(pub_border_, border_indices, header);
00148 publishCloud(pub_veil_, veil_indices, header);
00149 publishCloud(pub_shadow_, shadow_indices, header);
00150 cv::Mat image;
00151 jsk_recognition_utils::rangeImageToCvMat(range_image, image);
00152 pub_range_image_.publish(
00153 cv_bridge::CvImage(header,
00154 sensor_msgs::image_encodings::BGR8,
00155 image).toImageMsg());
00156
00157 sensor_msgs::PointCloud2 ros_cloud;
00158 pcl::toROSMsg(range_image, ros_cloud);
00159 ros_cloud.header = header;
00160 pub_cloud_.publish(ros_cloud);
00161 }
00162
00163 void BorderEstimator::estimate(
00164 const sensor_msgs::PointCloud2::ConstPtr& msg,
00165 const sensor_msgs::CameraInfo::ConstPtr& info)
00166 {
00167 if (msg->height == 1) {
00168 NODELET_ERROR("[BorderEstimator::estimate] pointcloud must be organized");
00169 return;
00170 }
00171 pcl::RangeImagePlanar range_image;
00172 pcl::PointCloud<pcl::PointXYZ> cloud;
00173 pcl::fromROSMsg(*msg, cloud);
00174 Eigen::Affine3f dummytrans = Eigen::Affine3f::Identity();
00175 float fx = info->P[0];
00176 float cx = info->P[2];
00177 float tx = info->P[3];
00178 float fy = info->P[5];
00179 float cy = info->P[6];
00180 range_image.createFromPointCloudWithFixedSize (cloud,
00181 msg->width,
00182 msg->height,
00183 cx, cy,
00184 fx, fy,
00185 dummytrans);
00186 range_image.setUnseenToMaxRange();
00187 computeBorder(range_image, msg->header);
00188 }
00189
00190 void BorderEstimator::configCallback(Config &config, uint32_t level)
00191 {
00192 boost::mutex::scoped_lock lock(mutex_);
00193 noise_level_ = config.noise_level;
00194 min_range_ = config.min_range;
00195 border_size_ = config.border_size;
00196 angular_resolution_ = config.angular_resolution;
00197 max_angle_height_ = config.max_angle_height;
00198 max_angle_width_ = config.max_angle_width;
00199 }
00200 }
00201
00202 #include <pluginlib/class_list_macros.h>
00203 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BorderEstimator,
00204 nodelet::Nodelet);