#include <heightmap_converter.h>
| Public Types | |
| typedef HeightmapConverterConfig | Config | 
| typedef boost::shared_ptr < HeightmapConverter > | Ptr | 
| Public Member Functions | |
| HeightmapConverter () | |
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | convert (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| virtual void | onInit () | 
| virtual void | subscribe () | 
| cv::Point | toIndex (const pcl::PointXYZ &p) const | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| std::string | center_frame_id_ | 
| std::string | fixed_frame_id_ | 
| double | initial_probability_ | 
| int | max_queue_size_ | 
| double | max_x_ | 
| double | max_y_ | 
| double | min_x_ | 
| double | min_y_ | 
| boost::mutex | mutex_ | 
| std::string | projected_center_frame_id_ | 
| ros::Publisher | pub_ | 
| ros::Publisher | pub_config_ | 
| int | resolution_x_ | 
| int | resolution_y_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| ros::Subscriber | sub_ | 
| tf::TransformListener * | tf_ | 
| tf::TransformBroadcaster | tf_broadcaster_ | 
| bool | use_projected_center_ | 
Definition at line 54 of file heightmap_converter.h.
| typedef HeightmapConverterConfig jsk_pcl_ros::HeightmapConverter::Config | 
Definition at line 58 of file heightmap_converter.h.
| typedef boost::shared_ptr<HeightmapConverter> jsk_pcl_ros::HeightmapConverter::Ptr | 
Definition at line 57 of file heightmap_converter.h.
| jsk_pcl_ros::HeightmapConverter::HeightmapConverter | ( | ) |  [inline] | 
Definition at line 59 of file heightmap_converter.h.
| void jsk_pcl_ros::HeightmapConverter::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 156 of file heightmap_converter_nodelet.cpp.
| void jsk_pcl_ros::HeightmapConverter::convert | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  [protected, virtual] | 
Definition at line 81 of file heightmap_converter_nodelet.cpp.
| void jsk_pcl_ros::HeightmapConverter::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 47 of file heightmap_converter_nodelet.cpp.
| void jsk_pcl_ros::HeightmapConverter::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 71 of file heightmap_converter_nodelet.cpp.
| cv::Point jsk_pcl_ros::HeightmapConverter::toIndex | ( | const pcl::PointXYZ & | p | ) | const  [inline, protected] | 
Definition at line 66 of file heightmap_converter.h.
| void jsk_pcl_ros::HeightmapConverter::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 76 of file heightmap_converter_nodelet.cpp.
Definition at line 93 of file heightmap_converter.h.
Definition at line 92 of file heightmap_converter.h.
| double jsk_pcl_ros::HeightmapConverter::initial_probability_  [protected] | 
Definition at line 96 of file heightmap_converter.h.
| int jsk_pcl_ros::HeightmapConverter::max_queue_size_  [protected] | 
Definition at line 91 of file heightmap_converter.h.
| double jsk_pcl_ros::HeightmapConverter::max_x_  [protected] | 
Definition at line 86 of file heightmap_converter.h.
| double jsk_pcl_ros::HeightmapConverter::max_y_  [protected] | 
Definition at line 88 of file heightmap_converter.h.
| double jsk_pcl_ros::HeightmapConverter::min_x_  [protected] | 
Definition at line 85 of file heightmap_converter.h.
| double jsk_pcl_ros::HeightmapConverter::min_y_  [protected] | 
Definition at line 87 of file heightmap_converter.h.
| boost::mutex jsk_pcl_ros::HeightmapConverter::mutex_  [protected] | 
Definition at line 80 of file heightmap_converter.h.
Definition at line 94 of file heightmap_converter.h.
| ros::Publisher jsk_pcl_ros::HeightmapConverter::pub_  [protected] | 
Definition at line 81 of file heightmap_converter.h.
Definition at line 82 of file heightmap_converter.h.
| int jsk_pcl_ros::HeightmapConverter::resolution_x_  [protected] | 
Definition at line 89 of file heightmap_converter.h.
| int jsk_pcl_ros::HeightmapConverter::resolution_y_  [protected] | 
Definition at line 90 of file heightmap_converter.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::HeightmapConverter::srv_  [protected] | 
Definition at line 84 of file heightmap_converter.h.
| ros::Subscriber jsk_pcl_ros::HeightmapConverter::sub_  [protected] | 
Definition at line 83 of file heightmap_converter.h.
Definition at line 98 of file heightmap_converter.h.
Definition at line 99 of file heightmap_converter.h.
| bool jsk_pcl_ros::HeightmapConverter::use_projected_center_  [protected] | 
Definition at line 95 of file heightmap_converter.h.