#include <pc_accumulation.h>
Public Member Functions | |
int | pointcloud_accumulated (pcl::PointCloud< pcl::PointXYZRGB > pcl_pc, std::string acc_frame_id) |
Main Function to accumulate pointCloud This function receives a pcl pointcloud and the accumulation frame. It looks for a transformation between the pcl frame_id and the accumulation frame_id. Proceeds with the transformation, and accumulates it on the class variable pcl_pc_acc. | |
int | pointcloud_accumulated (sensor_msgs::PointCloud2 &pc_in, std::string acc_frame_id) |
Function that receive a PointCloud2 and Accumulation Frame If PointCloud2 has no field "rgb" then it is responsible to add it. | |
int | pointcloud_accumulated (sensor_msgs::LaserScan &scan_in, std::string acc_frame_id) |
Function that receive a LaserScan and Accumulation Frame It converts the laserScan to a pcl::PointXYZRGB and call's the pointcloud_accumulated (main function). | |
int | remove_points_from_pointcloud (pcl::PointCloud< pcl::PointXYZRGB > pcl_pc, float dist, float X0, float Y0, float Z0) |
Removes points of pointclouds, given a distance and remove_frame. This function calculates the distance between each pcl_point and the remove_frame origin. If the point is farther then the desired distance, it is removed from the pcl. | |
int | remove_points_from_pointcloud (pcl::PointCloud< pcl::PointXYZRGB > pcl_pc, float dist, std::string frame_id) |
Function the removes points from cloud This function calculated the origin of the given accumulation frame_id. | |
Public Attributes | |
std::string | _acc_frame_id |
sensor_msgs::PointCloud2 | msg_cloud |
nav_msgs::Odometry | odometry_ |
tf::TransformListener * | p_listener |
ros::NodeHandle * | p_n |
pcl::PointCloud< pcl::PointXYZRGB > | pcl_pc_acc |
ros::Time | time_msg |
double | voxel_size |
Class to accumulate point_clouds
Definition at line 55 of file pc_accumulation.h.
int pc_accumulation::pointcloud_accumulated | ( | pcl::PointCloud< pcl::PointXYZRGB > | pcl_pc, | |
std::string | acc_frame_id | |||
) |
Main Function to accumulate pointCloud This function receives a pcl pointcloud and the accumulation frame.
It looks for a transformation between the pcl frame_id and the accumulation frame_id.
Proceeds with the transformation, and accumulates it on the class variable pcl_pc_acc.
[in] | pcl::PointCloud<pcl::PointXYZRGB> | |
[in] | std::string |
Definition at line 64 of file pc_accumulation.cpp.
int pc_accumulation::pointcloud_accumulated | ( | sensor_msgs::PointCloud2 & | pc_in, | |
std::string | acc_frame_id | |||
) | [inline] |
Function that receive a PointCloud2 and Accumulation Frame If PointCloud2 has no field "rgb" then it is responsible to add it.
[in] | sensor_msgs::PointCloud2 | |
[in] | std::string |
Definition at line 114 of file pc_accumulation.h.
int pc_accumulation::pointcloud_accumulated | ( | sensor_msgs::LaserScan & | scan_in, | |
std::string | acc_frame_id | |||
) | [inline] |
Function that receive a LaserScan and Accumulation Frame It converts the laserScan to a pcl::PointXYZRGB and call's the pointcloud_accumulated (main function).
[in] | sensor_msgs::LaserScan | |
[in] | std::string |
Definition at line 77 of file pc_accumulation.h.
int pc_accumulation::remove_points_from_pointcloud | ( | pcl::PointCloud< pcl::PointXYZRGB > | pcl_pc, | |
float | dist, | |||
float | X0, | |||
float | Y0, | |||
float | Z0 | |||
) |
Removes points of pointclouds, given a distance and remove_frame. This function calculates the distance between each pcl_point and the remove_frame origin.
If the point is farther then the desired distance, it is removed from the pcl.
[in] | pcl::PointCloud<pcl::PointXYZRGB> | |
[in] | dist | |
[in] | X0 | |
[in] | Y0 | |
[in] | Z0 |
Definition at line 132 of file pc_accumulation.cpp.
int pc_accumulation::remove_points_from_pointcloud | ( | pcl::PointCloud< pcl::PointXYZRGB > | pcl_pc, | |
float | dist, | |||
std::string | frame_id | |||
) | [inline] |
Function the removes points from cloud This function calculated the origin of the given accumulation frame_id.
[in] | pcl::PointCloud<pcl::PointXYZRGB> | |
[in] | float | |
[in] | std::string |
Definition at line 157 of file pc_accumulation.h.
std::string pc_accumulation::_acc_frame_id |
Definition at line 62 of file pc_accumulation.h.
sensor_msgs::PointCloud2 pc_accumulation::msg_cloud |
Definition at line 67 of file pc_accumulation.h.
nav_msgs::Odometry pc_accumulation::odometry_ |
Definition at line 64 of file pc_accumulation.h.
tf::TransformListener* pc_accumulation::p_listener |
Definition at line 59 of file pc_accumulation.h.
ros::NodeHandle* pc_accumulation::p_n |
Definition at line 60 of file pc_accumulation.h.
pcl::PointCloud<pcl::PointXYZRGB> pc_accumulation::pcl_pc_acc |
Definition at line 69 of file pc_accumulation.h.
ros::Time pc_accumulation::time_msg |
Definition at line 65 of file pc_accumulation.h.
double pc_accumulation::voxel_size |
Definition at line 61 of file pc_accumulation.h.