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/heightmap_to_pointcloud.h"
00039 #include <pcl_conversions/pcl_conversions.h>
00040 #include <cv_bridge/cv_bridge.h>
00041 #include <sensor_msgs/image_encodings.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044
00045 namespace jsk_pcl_ros
00046 {
00047 void HeightmapToPointCloud::onInit()
00048 {
00049 DiagnosticNodelet::onInit();
00050 pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
00051 "output/config", 1);
00052 sub_config_ = pnh_->subscribe(
00053 getHeightmapConfigTopic(pnh_->resolveName("input")), 1,
00054 &HeightmapToPointCloud::configCallback, this);
00055 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00056 }
00057
00058 void HeightmapToPointCloud::subscribe()
00059 {
00060 sub_ = pnh_->subscribe("input", 1, &HeightmapToPointCloud::convert, this);
00061 }
00062
00063 void HeightmapToPointCloud::unsubscribe()
00064 {
00065 sub_.shutdown();
00066 }
00067
00068 void HeightmapToPointCloud::configCallback(
00069 const jsk_recognition_msgs::HeightmapConfig::ConstPtr& msg)
00070 {
00071 boost::mutex::scoped_lock lock(mutex_);
00072 config_msg_ = msg;
00073 min_x_ = msg->min_x;
00074 max_x_ = msg->max_x;
00075 min_y_ = msg->min_y;
00076 max_y_ = msg->max_y;
00077 pub_config_.publish(msg);
00078 }
00079
00080 void HeightmapToPointCloud::convert(const sensor_msgs::Image::ConstPtr& msg)
00081 {
00082 boost::mutex::scoped_lock lock(mutex_);
00083 if (!config_msg_) {
00084 JSK_NODELET_ERROR("no ~input/config is yet available");
00085 return;
00086 }
00087 cv::Mat float_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_32FC1)->image;
00088 pcl::PointCloud<pcl::PointXYZ> cloud;
00089 cloud.points.reserve(float_image.rows * float_image.cols);
00090 double dx = (max_x_ - min_x_) / float_image.cols;
00091 double dy = (max_y_ - min_y_) / float_image.rows;
00092 for (size_t j = 0; j < float_image.rows; j++) {
00093 for (size_t i = 0; i < float_image.cols; i++) {
00094 float v = float_image.at<float>(j, i);
00095 pcl::PointXYZ p;
00096 if (v != -FLT_MAX) {
00097 p.y = j * dy + min_y_ + dy / 2.0;
00098 p.x = i * dx + min_x_ + dx / 2.0;
00099 p.z = v;
00100 cloud.points.push_back(p);
00101 }
00102 }
00103 }
00104 sensor_msgs::PointCloud2 ros_cloud;
00105 pcl::toROSMsg(cloud, ros_cloud);
00106 ros_cloud.header = msg->header;
00107 pub_.publish(ros_cloud);
00108 }
00109 }
00110
00111 #include <pluginlib/class_list_macros.h>
00112 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HeightmapToPointCloud, nodelet::Nodelet);
00113