36 #define BOOST_PARAMETER_MAX_ARITY 7 42 #include <pcl/point_cloud.h> 43 #include <pcl/point_types.h> 49 DiagnosticNodelet::onInit();
55 pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
70 const jsk_recognition_msgs::HeightmapConfig::ConstPtr&
msg)
90 pcl::PointCloud<HeightMapPointType >
cloud;
93 pnh_->param(
"keep_organized", keep_organized,
false);
101 sensor_msgs::PointCloud2 ros_cloud;
103 ros_cloud.header = msg->header;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
jsk_recognition_msgs::HeightmapConfig::ConstPtr config_msg_
#define NODELET_ERROR(...)
ros::Publisher pub_config_
void publish(const boost::shared_ptr< M > &message) const
std::string getHeightmapConfigTopic(const std::string &base_topic)
virtual void convert(const sensor_msgs::Image::ConstPtr &msg)
void convertHeightMapToPCLOrganize(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HeightmapToPointCloud, nodelet::Nodelet)
virtual void unsubscribe()
virtual void configCallback(const jsk_recognition_msgs::HeightmapConfig::ConstPtr &msg)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
ros::Subscriber sub_config_
void convertHeightMapToPCL(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)
const std::string TYPE_32FC2