Go to the documentation of this file.
   36 #define BOOST_PARAMETER_MAX_ARITY 7 
   42 #include <pcl/point_cloud.h> 
   43 #include <pcl/point_types.h> 
   49     DiagnosticNodelet::onInit();
 
   50     pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
 
   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;
 
  
#define NODELET_ERROR(...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HeightmapToPointCloud, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
void convertHeightMapToPCL(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)
std::string getHeightmapConfigTopic(const std::string &base_topic)
jsk_recognition_msgs::HeightmapConfig::ConstPtr config_msg_
ros::Publisher pub_config_
virtual void convert(const sensor_msgs::Image::ConstPtr &msg)
const std::string TYPE_32FC2
virtual void configCallback(const jsk_recognition_msgs::HeightmapConfig::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_)
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
ros::Subscriber sub_config_
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
virtual void unsubscribe()
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11