Go to the documentation of this file.
   36 #ifndef JSK_PCL_ROS_HEIGHTMAP_CONVERTER_H_ 
   37 #define JSK_PCL_ROS_HEIGHTMAP_CONVERTER_H_ 
   39 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   41 #include <sensor_msgs/PointCloud2.h> 
   42 #include <jsk_pcl_ros/HeightmapConverterConfig.h> 
   43 #include <dynamic_reconfigure/server.h> 
   44 #include <opencv2/opencv.hpp> 
   45 #include <pcl/point_types.h> 
   46 #include <pcl/point_cloud.h> 
   47 #include <jsk_recognition_msgs/HeightmapConfig.h> 
   54   class HeightmapConverter: 
public jsk_topic_tools::DiagnosticNodelet
 
   58     typedef HeightmapConverterConfig 
Config;
 
   65     virtual void convert(
const sensor_msgs::PointCloud2::ConstPtr& 
msg);
 
   66     inline cv::Point 
toIndex(
const pcl::PointXYZ& p)
 const 
   70         return cv::Point(-1, -1);
 
   72       const float offsetted_x = 
p.x - 
min_x_;
 
   73       const float offsetted_y = 
p.y - 
min_y_;
 
   76       return cv::Point(std::floor(offsetted_x / dx),
 
   77                        std::floor(offsetted_y / dy));
 
  
std::string center_frame_id_
std::string fixed_frame_id_
ros::Publisher pub_config_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
tf::TransformBroadcaster tf_broadcaster_
double initial_probability_
std::string projected_center_frame_id_
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< HeightmapConverter > Ptr
cv::Point toIndex(const pcl::PointXYZ &p) const
bool use_projected_center_
HeightmapConverterConfig Config
double duration_transform_timeout_
virtual void configCallback(Config &config, uint32_t level)
boost::mutex mutex
global mutex.
virtual void unsubscribe()
tf::TransformListener * tf_
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11