#include <pc_accumulation.h>
|
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) More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
Class to accumulate point_clouds
- Date
- March 2012
- Author
- Pedro Salvado
Definition at line 55 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)
- Parameters
-
[in] | sensor_msgs::LaserScan | |
[in] | std::string | |
Definition at line 77 of file pc_accumulation.h.
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.
- Parameters
-
[in] | sensor_msgs::PointCloud2 | |
[in] | std::string | |
Definition at line 121 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.
- Parameters
-
[in] | pcl::PointCloud<pcl::PointXYZRGB> | |
[in] | std::string | |
- Returns
- transform from a projected point
Definition at line 65 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.
- Parameters
-
[in] | pcl::PointCloud<pcl::PointXYZRGB> | |
[in] | float | |
[in] | std::string | |
Definition at line 164 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.
- Parameters
-
[in] | pcl::PointCloud<pcl::PointXYZRGB> | |
[in] | dist | |
[in] | X0 | |
[in] | Y0 | |
[in] | Z0 | |
Definition at line 147 of file pc_accumulation.cpp.
std::string pc_accumulation::_acc_frame_id |
sensor_msgs::PointCloud2 pc_accumulation::msg_cloud |
nav_msgs::Odometry pc_accumulation::odometry_ |
tf::TransformListener* pc_accumulation::p_listener |
ros::NodeHandle* pc_accumulation::p_n |
pcl::PointCloud<pcl::PointXYZRGB> pc_accumulation::pcl_pc_acc |
ros::Time pc_accumulation::time_msg |
double pc_accumulation::voxel_size |
The documentation for this class was generated from the following files: