Classes | |
struct | OdomMsg |
Public Types | |
typedef pcl::PointXYZRGB | Point |
typedef pcl::PointXYZRGB | Point |
typedef pcl::PointCloud < pcl::PointXYZRGB > | PointCloud |
typedef pcl::PointCloud < pcl::PointXYZRGB > | PointCloud |
Public Member Functions | |
void | callback (const sensor_msgs::PointCloud2ConstPtr &cloud_msg) |
void | callback (const sensor_msgs::PointCloud2ConstPtr &cloud) |
bool | fileExists (const char *filename) |
PointCloud::Ptr | filter (PointCloud::Ptr cloud) |
PointCloud::Ptr | filter (PointCloud::Ptr cloud) |
PointCloudMapper () | |
PointCloudMapper () | |
void | publishCallback (const ros::WallTimerEvent &) |
void | timerCallback (const ros::WallTimerEvent &event) |
Private Attributes | |
PointCloud | accumulated_cloud_ |
ros::Publisher | cloud_pub_ |
ros::Subscriber | cloud_sub_ |
bool | filter_map_ |
std::string | fixed_frame_ |
std::string | graph_blocking_file_ |
std::string | graph_vertices_file_ |
ros::WallTime | last_pub_time_ |
int | mean_k_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_priv_ |
std::vector < sensor_msgs::PointCloud2 > | pointcloud_list_ |
ros::WallTimer | pub_timer_ |
double | std_dev_thresh_ |
tf::TransformListener | tf_listener_ |
double | voxel_size_ |
double | x_filter_max_ |
double | x_filter_min_ |
double | y_filter_max_ |
double | y_filter_min_ |
double | z_filter_max_ |
double | z_filter_min_ |
Stores incoming point clouds in a map transforming each cloud to a global fixed frame using tf.
Definition at line 13 of file pointcloud_mapper.cpp.
typedef pcl::PointXYZRGB PointCloudMapper::Point |
Definition at line 17 of file pointcloud_mapper.cpp.
typedef pcl::PointXYZRGB PointCloudMapper::Point |
Definition at line 21 of file pointcloud_mapper_for_slam.cpp.
typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloudMapper::PointCloud |
Definition at line 18 of file pointcloud_mapper.cpp.
typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloudMapper::PointCloud |
Definition at line 22 of file pointcloud_mapper_for_slam.cpp.
PointCloudMapper::PointCloudMapper | ( | ) | [inline] |
Definition at line 20 of file pointcloud_mapper.cpp.
PointCloudMapper::PointCloudMapper | ( | ) | [inline] |
Definition at line 24 of file pointcloud_mapper_for_slam.cpp.
void PointCloudMapper::callback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud_msg | ) | [inline] |
Definition at line 48 of file pointcloud_mapper.cpp.
void PointCloudMapper::callback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [inline] |
Definition at line 48 of file pointcloud_mapper_for_slam.cpp.
bool PointCloudMapper::fileExists | ( | const char * | filename | ) | [inline] |
Definition at line 235 of file pointcloud_mapper_for_slam.cpp.
PointCloud::Ptr PointCloudMapper::filter | ( | PointCloud::Ptr | cloud | ) | [inline] |
Definition at line 101 of file pointcloud_mapper.cpp.
PointCloud::Ptr PointCloudMapper::filter | ( | PointCloud::Ptr | cloud | ) | [inline] |
Definition at line 189 of file pointcloud_mapper_for_slam.cpp.
void PointCloudMapper::publishCallback | ( | const ros::WallTimerEvent & | ) | [inline] |
Definition at line 89 of file pointcloud_mapper.cpp.
void PointCloudMapper::timerCallback | ( | const ros::WallTimerEvent & | event | ) | [inline] |
Definition at line 72 of file pointcloud_mapper_for_slam.cpp.
Definition at line 164 of file pointcloud_mapper.cpp.
ros::Publisher PointCloudMapper::cloud_pub_ [private] |
Definition at line 160 of file pointcloud_mapper.cpp.
ros::Subscriber PointCloudMapper::cloud_sub_ [private] |
Definition at line 159 of file pointcloud_mapper.cpp.
bool PointCloudMapper::filter_map_ [private] |
Definition at line 152 of file pointcloud_mapper.cpp.
std::string PointCloudMapper::fixed_frame_ [private] |
Definition at line 162 of file pointcloud_mapper.cpp.
std::string PointCloudMapper::graph_blocking_file_ [private] |
Definition at line 266 of file pointcloud_mapper_for_slam.cpp.
std::string PointCloudMapper::graph_vertices_file_ [private] |
Definition at line 265 of file pointcloud_mapper_for_slam.cpp.
Definition at line 165 of file pointcloud_mapper.cpp.
int PointCloudMapper::mean_k_ [private] |
Definition at line 277 of file pointcloud_mapper_for_slam.cpp.
ros::NodeHandle PointCloudMapper::nh_ [private] |
Definition at line 154 of file pointcloud_mapper.cpp.
ros::NodeHandle PointCloudMapper::nh_priv_ [private] |
Definition at line 155 of file pointcloud_mapper.cpp.
std::vector<sensor_msgs::PointCloud2> PointCloudMapper::pointcloud_list_ [private] |
Definition at line 288 of file pointcloud_mapper_for_slam.cpp.
ros::WallTimer PointCloudMapper::pub_timer_ [private] |
Definition at line 157 of file pointcloud_mapper.cpp.
double PointCloudMapper::std_dev_thresh_ [private] |
Definition at line 276 of file pointcloud_mapper_for_slam.cpp.
Definition at line 163 of file pointcloud_mapper.cpp.
double PointCloudMapper::voxel_size_ [private] |
Definition at line 151 of file pointcloud_mapper.cpp.
double PointCloudMapper::x_filter_max_ [private] |
Definition at line 146 of file pointcloud_mapper.cpp.
double PointCloudMapper::x_filter_min_ [private] |
Definition at line 145 of file pointcloud_mapper.cpp.
double PointCloudMapper::y_filter_max_ [private] |
Definition at line 148 of file pointcloud_mapper.cpp.
double PointCloudMapper::y_filter_min_ [private] |
Definition at line 147 of file pointcloud_mapper.cpp.
double PointCloudMapper::z_filter_max_ [private] |
Definition at line 150 of file pointcloud_mapper.cpp.
double PointCloudMapper::z_filter_min_ [private] |
Definition at line 149 of file pointcloud_mapper.cpp.