#include <heightmap_time_accumulation.h>
◆ Accumulator
◆ Config
◆ Ptr
◆ HeightmapTimeAccumulation()
jsk_pcl_ros::HeightmapTimeAccumulation::HeightmapTimeAccumulation |
( |
| ) |
|
|
inline |
◆ accumulate()
void jsk_pcl_ros::HeightmapTimeAccumulation::accumulate |
( |
const sensor_msgs::Image::ConstPtr & |
new_heightmap | ) |
|
|
protectedvirtual |
◆ configCallback()
void jsk_pcl_ros::HeightmapTimeAccumulation::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ configTopicCallback()
void jsk_pcl_ros::HeightmapTimeAccumulation::configTopicCallback |
( |
const jsk_recognition_msgs::HeightmapConfig::ConstPtr & |
config | ) |
|
|
protectedvirtual |
◆ isValidCell()
bool jsk_pcl_ros::HeightmapTimeAccumulation::isValidCell |
( |
const cv::Point & |
index, |
|
|
const cv::Mat & |
map |
|
) |
| |
|
protectedvirtual |
◆ isValidIndex()
bool jsk_pcl_ros::HeightmapTimeAccumulation::isValidIndex |
( |
const cv::Point & |
index, |
|
|
const cv::Mat & |
map |
|
) |
| |
|
protectedvirtual |
◆ mergedAccmulation()
void jsk_pcl_ros::HeightmapTimeAccumulation::mergedAccmulation |
( |
pcl::PointCloud< PointType > & |
transformed_pointcloud, |
|
|
cv::Mat & |
new_heightmap |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::HeightmapTimeAccumulation::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ overwriteAccmulation()
void jsk_pcl_ros::HeightmapTimeAccumulation::overwriteAccmulation |
( |
pcl::PointCloud< PointType > & |
transformed_pointcloud, |
|
|
cv::Mat & |
new_heightmap |
|
) |
| |
|
protectedvirtual |
◆ prevPointCloud()
void jsk_pcl_ros::HeightmapTimeAccumulation::prevPointCloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ publishHeightmap()
void jsk_pcl_ros::HeightmapTimeAccumulation::publishHeightmap |
( |
const cv::Mat & |
heightmap, |
|
|
const std_msgs::Header & |
header |
|
) |
| |
|
protectedvirtual |
◆ resetCallback()
bool jsk_pcl_ros::HeightmapTimeAccumulation::resetCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::HeightmapTimeAccumulation::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ toIndex()
cv::Point jsk_pcl_ros::HeightmapTimeAccumulation::toIndex |
( |
const PointType & |
p, |
|
|
const cv::Mat & |
map |
|
) |
| |
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::HeightmapTimeAccumulation::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ accumulated_heightmap_
cv::Mat jsk_pcl_ros::HeightmapTimeAccumulation::accumulated_heightmap_ |
|
protected |
◆ bilateral_filter_size_
int jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_filter_size_ |
|
protected |
◆ bilateral_sigma_color_
double jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_sigma_color_ |
|
protected |
◆ bilateral_sigma_space_
double jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_sigma_space_ |
|
protected |
◆ center_frame_id_
std::string jsk_pcl_ros::HeightmapTimeAccumulation::center_frame_id_ |
|
protected |
◆ config_
jsk_recognition_msgs::HeightmapConfig::ConstPtr jsk_pcl_ros::HeightmapTimeAccumulation::config_ |
|
protected |
◆ fixed_frame_id_
std::string jsk_pcl_ros::HeightmapTimeAccumulation::fixed_frame_id_ |
|
protected |
◆ max_x_
double jsk_pcl_ros::HeightmapTimeAccumulation::max_x_ |
|
protected |
◆ max_y_
double jsk_pcl_ros::HeightmapTimeAccumulation::max_y_ |
|
protected |
◆ min_x_
double jsk_pcl_ros::HeightmapTimeAccumulation::min_x_ |
|
protected |
◆ min_y_
double jsk_pcl_ros::HeightmapTimeAccumulation::min_y_ |
|
protected |
◆ mutex_
◆ prev_cloud_
◆ prev_from_center_to_fixed_
Eigen::Affine3f jsk_pcl_ros::HeightmapTimeAccumulation::prev_from_center_to_fixed_ |
|
protected |
◆ pub_config_
◆ pub_output_
◆ srv_
◆ srv_reset_
◆ sub_config_
◆ sub_heightmap_
◆ sub_previous_pointcloud_
ros::Subscriber jsk_pcl_ros::HeightmapTimeAccumulation::sub_previous_pointcloud_ |
|
protected |
◆ tf_
◆ tf_filter_
◆ tf_queue_size_
int jsk_pcl_ros::HeightmapTimeAccumulation::tf_queue_size_ |
|
protected |
◆ use_bilateral_
bool jsk_pcl_ros::HeightmapTimeAccumulation::use_bilateral_ |
|
protected |
◆ use_offset_
bool jsk_pcl_ros::HeightmapTimeAccumulation::use_offset_ |
|
protected |
The documentation for this class was generated from the following files: