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 onInitPostProcess();
00057 }
00058
00059 void HeightmapToPointCloud::subscribe()
00060 {
00061 sub_ = pnh_->subscribe("input", 1, &HeightmapToPointCloud::convert, this);
00062 }
00063
00064 void HeightmapToPointCloud::unsubscribe()
00065 {
00066 sub_.shutdown();
00067 }
00068
00069 void HeightmapToPointCloud::configCallback(
00070 const jsk_recognition_msgs::HeightmapConfig::ConstPtr& msg)
00071 {
00072 boost::mutex::scoped_lock lock(mutex_);
00073 config_msg_ = msg;
00074 min_x_ = msg->min_x;
00075 max_x_ = msg->max_x;
00076 min_y_ = msg->min_y;
00077 max_y_ = msg->max_y;
00078 pub_config_.publish(msg);
00079 }
00080
00081 void HeightmapToPointCloud::convert(const sensor_msgs::Image::ConstPtr& msg)
00082 {
00083 boost::mutex::scoped_lock lock(mutex_);
00084 if (!config_msg_) {
00085 NODELET_ERROR("no ~input/config is yet available");
00086 return;
00087 }
00088
00089 cv::Mat float_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_32FC2)->image;
00090 pcl::PointCloud<HeightMapPointType > cloud;
00091
00092 bool keep_organized;
00093 pnh_->param("keep_organized", keep_organized, false);
00094 if (keep_organized) {
00095 convertHeightMapToPCLOrganize(float_image, cloud, max_x_, min_x_, max_y_, min_y_);
00096 }
00097 else {
00098 convertHeightMapToPCL(float_image, cloud, max_x_, min_x_, max_y_, min_y_);
00099 }
00100
00101 sensor_msgs::PointCloud2 ros_cloud;
00102 pcl::toROSMsg(cloud, ros_cloud);
00103 ros_cloud.header = msg->header;
00104 pub_.publish(ros_cloud);
00105 }
00106 }
00107
00108 #include <pluginlib/class_list_macros.h>
00109 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HeightmapToPointCloud, nodelet::Nodelet);