36 #define BOOST_PARAMETER_MAX_ARITY 7 38 #include <pcl/range_image/range_image_planar.h> 39 #include <pcl/range_image/range_image_spherical.h> 48 ConnectionBasedNodelet::onInit();
51 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
52 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
54 srv_->setCallback (f);
56 pub_border_ = advertise<PCLIndicesMsg>(*
pnh_,
"output_border_indices", 1);
57 pub_veil_ = advertise<PCLIndicesMsg>(*
pnh_,
"output_veil_indices", 1);
58 pub_shadow_ = advertise<PCLIndicesMsg>(*
pnh_,
"output_shadow_indices", 1);
60 *
pnh_,
"output_range_image", 1);
61 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
62 *
pnh_,
"output_cloud", 1);
72 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
94 const pcl::PointIndices& inlier,
95 const std_msgs::Header&
header)
99 msg.indices = inlier.indices;
104 const sensor_msgs::PointCloud2::ConstPtr&
msg)
107 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZ>);
109 pcl::RangeImage range_image;
111 range_image = pcl::RangeImageSpherical();
113 range_image.createFromPointCloud(
117 Eigen::Affine3f::Identity(),
118 pcl::RangeImage::CAMERA_FRAME,
122 range_image.setUnseenToMaxRange();
127 const pcl::RangeImage& range_image,
128 const std_msgs::Header&
header)
130 pcl::RangeImageBorderExtractor border_extractor (&range_image);
131 pcl::PointCloud<pcl::BorderDescription> border_descriptions;
132 border_extractor.compute (border_descriptions);
133 pcl::PointIndices border_indices, veil_indices, shadow_indices;
134 for (
int y = 0;
y < (int)range_image.height; ++
y) {
135 for (
int x = 0;
x < (int)range_image.width; ++
x) {
136 if (border_descriptions.points[
y*range_image.width +
x].traits[pcl::BORDER_TRAIT__OBSTACLE_BORDER]) {
137 border_indices.indices.push_back (
y*range_image.width +
x);
139 if (border_descriptions.points[
y*range_image.width +
x].traits[pcl::BORDER_TRAIT__VEIL_POINT]) {
140 veil_indices.indices.push_back (
y*range_image.width +
x);
142 if (border_descriptions.points[
y*range_image.width +
x].traits[pcl::BORDER_TRAIT__SHADOW_BORDER]) {
143 shadow_indices.indices.push_back (
y*range_image.width +
x);
155 image).toImageMsg());
157 sensor_msgs::PointCloud2 ros_cloud;
159 ros_cloud.header =
header;
164 const sensor_msgs::PointCloud2::ConstPtr&
msg,
165 const sensor_msgs::CameraInfo::ConstPtr& info)
167 if (msg->height == 1) {
168 NODELET_ERROR(
"[BorderEstimator::estimate] pointcloud must be organized");
171 pcl::RangeImagePlanar range_image;
172 pcl::PointCloud<pcl::PointXYZ>
cloud;
174 Eigen::Affine3f dummytrans = Eigen::Affine3f::Identity();
175 float fx = info->P[0];
176 float cx = info->P[2];
177 float tx = info->P[3];
178 float fy = info->P[5];
179 float cy = info->P[6];
180 range_image.createFromPointCloudWithFixedSize (cloud,
186 range_image.setUnseenToMaxRange();
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BorderEstimator, nodelet::Nodelet)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
BorderEstimatorConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo)
ros::Publisher pub_shadow_
ros::Publisher pub_border_
virtual void configCallback(Config &config, uint32_t level)
void rangeImageToCvMat(const pcl::RangeImage &range_image, cv::Mat &mat)
virtual void publishCloud(ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header)
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_cloud_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void computeBorder(const pcl::RangeImage &image, const std_msgs::Header &header)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
double angular_resolution_
ros::Publisher pub_range_image_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointIndices PCLIndicesMsg