#include <heightmap_time_accumulation.h>
Public Types | |
typedef boost::accumulators::accumulator_set < float, boost::accumulators::stats < boost::accumulators::tag::variance, boost::accumulators::tag::count, boost::accumulators::tag::mean > > | Accumulator |
typedef HeightmapTimeAccumulationConfig | Config |
typedef boost::shared_ptr < HeightmapTimeAccumulation > | Ptr |
Public Member Functions | |
HeightmapTimeAccumulation () | |
Protected Member Functions | |
virtual void | accumulate (const sensor_msgs::Image::ConstPtr &new_heightmap) |
virtual void | configCallback (Config &config, uint32_t level) |
virtual void | configTopicCallback (const jsk_recognition_msgs::HeightmapConfig::ConstPtr &config) |
virtual bool | isValidCell (const cv::Point &index, const cv::Mat &map) |
virtual bool | isValidIndex (const cv::Point &index, const cv::Mat &map) |
virtual void | mergedAccmulation (pcl::PointCloud< PointType > &transformed_pointcloud, cv::Mat &new_heightmap) |
virtual void | onInit () |
virtual void | overwriteAccmulation (pcl::PointCloud< PointType > &transformed_pointcloud, cv::Mat &new_heightmap) |
virtual void | prevPointCloud (const sensor_msgs::PointCloud2::ConstPtr &msg) |
virtual void | publishHeightmap (const cv::Mat &heightmap, const std_msgs::Header &header) |
virtual bool | resetCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
virtual void | subscribe () |
virtual cv::Point | toIndex (const PointType &p, const cv::Mat &map) |
virtual void | unsubscribe () |
Protected Attributes | |
cv::Mat | accumulated_heightmap_ |
int | bilateral_filter_size_ |
double | bilateral_sigma_color_ |
double | bilateral_sigma_space_ |
std::string | center_frame_id_ |
jsk_recognition_msgs::HeightmapConfig::ConstPtr | config_ |
std::string | fixed_frame_id_ |
double | max_x_ |
double | max_y_ |
double | min_x_ |
double | min_y_ |
boost::mutex | mutex_ |
pcl::PointCloud< PointType > | prev_cloud_ |
Eigen::Affine3f | prev_from_center_to_fixed_ |
ros::Publisher | pub_config_ |
ros::Publisher | pub_output_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
ros::ServiceServer | srv_reset_ |
ros::Subscriber | sub_config_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_heightmap_ |
ros::Subscriber | sub_previous_pointcloud_ |
tf::TransformListener * | tf_ |
boost::shared_ptr < tf::MessageFilter < sensor_msgs::Image > > | tf_filter_ |
int | tf_queue_size_ |
bool | use_bilateral_ |
bool | use_offset_ |
Definition at line 65 of file heightmap_time_accumulation.h.
typedef boost::accumulators::accumulator_set< float, boost::accumulators::stats< boost::accumulators::tag::variance, boost::accumulators::tag::count, boost::accumulators::tag::mean> > jsk_pcl_ros::HeightmapTimeAccumulation::Accumulator |
Definition at line 76 of file heightmap_time_accumulation.h.
typedef HeightmapTimeAccumulationConfig jsk_pcl_ros::HeightmapTimeAccumulation::Config |
Definition at line 70 of file heightmap_time_accumulation.h.
typedef boost::shared_ptr<HeightmapTimeAccumulation> jsk_pcl_ros::HeightmapTimeAccumulation::Ptr |
Definition at line 69 of file heightmap_time_accumulation.h.
Definition at line 77 of file heightmap_time_accumulation.h.
void jsk_pcl_ros::HeightmapTimeAccumulation::accumulate | ( | const sensor_msgs::Image::ConstPtr & | new_heightmap | ) | [protected, virtual] |
Definition at line 133 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 312 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::configTopicCallback | ( | const jsk_recognition_msgs::HeightmapConfig::ConstPtr & | config | ) | [protected, virtual] |
Definition at line 291 of file heightmap_time_accumulation_nodelet.cpp.
bool jsk_pcl_ros::HeightmapTimeAccumulation::isValidCell | ( | const cv::Point & | index, |
const cv::Mat & | map | ||
) | [protected, virtual] |
Definition at line 127 of file heightmap_time_accumulation_nodelet.cpp.
bool jsk_pcl_ros::HeightmapTimeAccumulation::isValidIndex | ( | const cv::Point & | index, |
const cv::Mat & | map | ||
) | [protected, virtual] |
Definition at line 121 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::mergedAccmulation | ( | pcl::PointCloud< PointType > & | transformed_pointcloud, |
cv::Mat & | new_heightmap | ||
) | [protected, virtual] |
Definition at line 186 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::onInit | ( | void | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 46 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::overwriteAccmulation | ( | pcl::PointCloud< PointType > & | transformed_pointcloud, |
cv::Mat & | new_heightmap | ||
) | [protected, virtual] |
Definition at line 161 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::prevPointCloud | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [protected, virtual] |
Definition at line 277 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::publishHeightmap | ( | const cv::Mat & | heightmap, |
const std_msgs::Header & | header | ||
) | [protected, virtual] |
Definition at line 97 of file heightmap_time_accumulation_nodelet.cpp.
bool jsk_pcl_ros::HeightmapTimeAccumulation::resetCallback | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) | [protected, virtual] |
Definition at line 303 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 87 of file heightmap_time_accumulation_nodelet.cpp.
cv::Point jsk_pcl_ros::HeightmapTimeAccumulation::toIndex | ( | const PointType & | p, |
const cv::Mat & | map | ||
) | [protected, virtual] |
Definition at line 106 of file heightmap_time_accumulation_nodelet.cpp.
void jsk_pcl_ros::HeightmapTimeAccumulation::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 91 of file heightmap_time_accumulation_nodelet.cpp.
cv::Mat jsk_pcl_ros::HeightmapTimeAccumulation::accumulated_heightmap_ [protected] |
Definition at line 107 of file heightmap_time_accumulation.h.
int jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_filter_size_ [protected] |
Definition at line 123 of file heightmap_time_accumulation.h.
double jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_sigma_color_ [protected] |
Definition at line 124 of file heightmap_time_accumulation.h.
double jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_sigma_space_ [protected] |
Definition at line 125 of file heightmap_time_accumulation.h.
std::string jsk_pcl_ros::HeightmapTimeAccumulation::center_frame_id_ [protected] |
Definition at line 105 of file heightmap_time_accumulation.h.
jsk_recognition_msgs::HeightmapConfig::ConstPtr jsk_pcl_ros::HeightmapTimeAccumulation::config_ [protected] |
Definition at line 116 of file heightmap_time_accumulation.h.
std::string jsk_pcl_ros::HeightmapTimeAccumulation::fixed_frame_id_ [protected] |
Definition at line 106 of file heightmap_time_accumulation.h.
double jsk_pcl_ros::HeightmapTimeAccumulation::max_x_ [protected] |
Definition at line 119 of file heightmap_time_accumulation.h.
double jsk_pcl_ros::HeightmapTimeAccumulation::max_y_ [protected] |
Definition at line 120 of file heightmap_time_accumulation.h.
double jsk_pcl_ros::HeightmapTimeAccumulation::min_x_ [protected] |
Definition at line 117 of file heightmap_time_accumulation.h.
double jsk_pcl_ros::HeightmapTimeAccumulation::min_y_ [protected] |
Definition at line 118 of file heightmap_time_accumulation.h.
Definition at line 101 of file heightmap_time_accumulation.h.
Definition at line 115 of file heightmap_time_accumulation.h.
Eigen::Affine3f jsk_pcl_ros::HeightmapTimeAccumulation::prev_from_center_to_fixed_ [protected] |
Definition at line 104 of file heightmap_time_accumulation.h.
Definition at line 109 of file heightmap_time_accumulation.h.
Definition at line 108 of file heightmap_time_accumulation.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::HeightmapTimeAccumulation::srv_ [protected] |
Definition at line 102 of file heightmap_time_accumulation.h.
Definition at line 110 of file heightmap_time_accumulation.h.
Definition at line 114 of file heightmap_time_accumulation.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::HeightmapTimeAccumulation::sub_heightmap_ [protected] |
Definition at line 112 of file heightmap_time_accumulation.h.
Definition at line 113 of file heightmap_time_accumulation.h.
Definition at line 103 of file heightmap_time_accumulation.h.
boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > jsk_pcl_ros::HeightmapTimeAccumulation::tf_filter_ [protected] |
Definition at line 111 of file heightmap_time_accumulation.h.
int jsk_pcl_ros::HeightmapTimeAccumulation::tf_queue_size_ [protected] |
Definition at line 121 of file heightmap_time_accumulation.h.
bool jsk_pcl_ros::HeightmapTimeAccumulation::use_bilateral_ [protected] |
Definition at line 126 of file heightmap_time_accumulation.h.
bool jsk_pcl_ros::HeightmapTimeAccumulation::use_offset_ [protected] |
Definition at line 122 of file heightmap_time_accumulation.h.