Public Member Functions | Public Attributes | Protected Attributes | List of all members
IncGroundRemoval Class Reference

Public Member Functions

void cloud_cb (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
void computeCentroid (const sample_consensus::PointCloud &points, const std::vector< int > &indices, pcl::PointXYZ &centroid)
 Compute the centroid of a set of points using their indices and return it as a Point32 message. More...
 
void computeCovarianceMatrix (const sample_consensus::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, pcl::PointXYZ &centroid)
 Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d. More...
 
void computePointNormal (const sample_consensus::PointCloud &points, const std::vector< int > &indices, Eigen::Vector4d &plane_parameters, double &curvature)
 Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature. More...
 
bool fitSACLine (sample_consensus::PointCloud *points, vector< int > *indices, vector< int > &inliers)
 Find a line model in a point cloud given via a set of point indices with SAmple Consensus methods. More...
 
void flipNormalTowardsViewpoint (Eigen::Vector4d &normal, const pcl::PointXYZ &point, const geometry_msgs::PointStamped &viewpoint)
 Flip (in place) the estimated normal of a point towards a given viewpoint. More...
 
void getCloudViewPoint (string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, tf::TransformListener *tf)
 Get the view point from where the scans were taken in the incoming sample_consensus::PointCloud message frame. More...
 
 IncGroundRemoval (ros::NodeHandle &anode)
 
double pointToPlaneDistanceSigned (const pcl::PointXYZ &p, const Eigen::Vector4d &plane_coefficients)
 Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0. More...
 
double transformDoubleValueTF (double val, std::string src_frame, std::string tgt_frame, ros::Time stamp, tf::TransformListener *tf)
 Transform a value from a source frame to a target frame at a certain moment in time with TF. More...
 
void transformPoint (tf::TransformListener *tf, const std::string &target_frame, const tf::Stamped< pcl::PointXYZ > &stamped_in, tf::Stamped< pcl::PointXYZ > &stamped_out)
 Transform a given point from its current frame to a given target frame. More...
 
void updateParametersFromServer ()
 
virtual ~IncGroundRemoval ()
 

Public Attributes

sample_consensus::PointCloud cloud_
 
sample_consensus::PointCloud cloud_noground_
 
tf::MessageFilter< sensor_msgs::PointCloud2 > * cloud_notifier_
 
ros::Publisher cloud_publisher_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * cloud_subscriber_
 
double ground_slope_threshold_
 
sample_consensus::PointCloud laser_cloud_
 
std::string laser_tilt_mount_frame_
 
int planar_refine_
 
std::string robot_footprint_frame_
 
double sac_distance_threshold_
 
double sac_fitting_distance_threshold_
 
int sac_max_iterations_
 
int sac_min_points_per_model_
 
tf::TransformListener tf_
 
geometry_msgs::PointStamped viewpoint_cloud_
 
double z_threshold_
 

Protected Attributes

ros::NodeHandlenode_
 

Detailed Description

Definition at line 64 of file sac_inc_ground_removal_standalone.cpp.

Constructor & Destructor Documentation

IncGroundRemoval::IncGroundRemoval ( ros::NodeHandle anode)
inline

Definition at line 90 of file sac_inc_ground_removal_standalone.cpp.

virtual IncGroundRemoval::~IncGroundRemoval ( )
inlinevirtual

Definition at line 133 of file sac_inc_ground_removal_standalone.cpp.

Member Function Documentation

void IncGroundRemoval::cloud_cb ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
inline

Definition at line 315 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::computeCentroid ( const sample_consensus::PointCloud points,
const std::vector< int > &  indices,
pcl::PointXYZ &  centroid 
)
inline

Compute the centroid of a set of points using their indices and return it as a Point32 message.

Parameters
pointsthe input point cloud
indicesthe point cloud indices that need to be used
centroidthe output centroid

Definition at line 224 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::computeCovarianceMatrix ( const sample_consensus::PointCloud points,
const std::vector< int > &  indices,
Eigen::Matrix3d &  covariance_matrix,
pcl::PointXYZ &  centroid 
)
inline

Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.

Note
The (x-y-z) centroid is also returned as a Point32 message.
Parameters
pointsthe input point cloud
indicesthe point cloud indices that need to be used
covariance_matrixthe 3x3 covariance matrix
centroidthe computed centroid

Definition at line 250 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::computePointNormal ( const sample_consensus::PointCloud points,
const std::vector< int > &  indices,
Eigen::Vector4d &  plane_parameters,
double &  curvature 
)
inline

Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature.

Parameters
pointsthe input point cloud
indicesthe point cloud indices that need to be used
plane_parametersthe plane parameters as: a, b, c, d (ax + by + cz + d = 0)
curvaturethe estimated surface curvature as a measure of

\[ \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) \]

Definition at line 285 of file sac_inc_ground_removal_standalone.cpp.

bool IncGroundRemoval::fitSACLine ( sample_consensus::PointCloud points,
vector< int > *  indices,
vector< int > &  inliers 
)
inline

Find a line model in a point cloud given via a set of point indices with SAmple Consensus methods.

Parameters
pointsthe point cloud message
indicesa pointer to a set of point cloud indices to test
inliersthe resultant inliers

Definition at line 152 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::flipNormalTowardsViewpoint ( Eigen::Vector4d &  normal,
const pcl::PointXYZ &  point,
const geometry_msgs::PointStamped &  viewpoint 
)
inline

Flip (in place) the estimated normal of a point towards a given viewpoint.

Parameters
normalthe plane normal to be flipped
pointa given point
viewpointthe viewpoint

Definition at line 196 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::getCloudViewPoint ( string  cloud_frame,
geometry_msgs::PointStamped &  viewpoint_cloud,
tf::TransformListener tf 
)
inline

Get the view point from where the scans were taken in the incoming sample_consensus::PointCloud message frame.

Parameters
cloud_framethe point cloud message TF frame
viewpoint_cloudthe resultant view point in the incoming cloud frame
tfa pointer to a TransformListener object

Definition at line 462 of file sac_inc_ground_removal_standalone.cpp.

double IncGroundRemoval::pointToPlaneDistanceSigned ( const pcl::PointXYZ &  p,
const Eigen::Vector4d &  plane_coefficients 
)
inline

Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.

Parameters
pa point
plane_coefficientsthe normalized coefficients (a, b, c, d) of a plane

Definition at line 450 of file sac_inc_ground_removal_standalone.cpp.

double IncGroundRemoval::transformDoubleValueTF ( double  val,
std::string  src_frame,
std::string  tgt_frame,
ros::Time  stamp,
tf::TransformListener tf 
)
inline

Transform a value from a source frame to a target frame at a certain moment in time with TF.

Parameters
valthe value to transform
src_framethe source frame to transform the value from
tgt_framethe target frame to transform the value into
stampa given time stamp
tfa pointer to a TransformListener object

Definition at line 530 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::transformPoint ( tf::TransformListener tf,
const std::string &  target_frame,
const tf::Stamped< pcl::PointXYZ > &  stamped_in,
tf::Stamped< pcl::PointXYZ > &  stamped_out 
)
inline

Transform a given point from its current frame to a given target frame.

Parameters
tfa pointer to a TransformListener object
target_framethe target frame to transform the point into
stamped_inthe input point
stamped_outthe output point

Definition at line 496 of file sac_inc_ground_removal_standalone.cpp.

void IncGroundRemoval::updateParametersFromServer ( )
inline

Definition at line 137 of file sac_inc_ground_removal_standalone.cpp.

Member Data Documentation

sample_consensus::PointCloud IncGroundRemoval::cloud_

Definition at line 72 of file sac_inc_ground_removal_standalone.cpp.

sample_consensus::PointCloud IncGroundRemoval::cloud_noground_

Definition at line 72 of file sac_inc_ground_removal_standalone.cpp.

tf::MessageFilter<sensor_msgs::PointCloud2>* IncGroundRemoval::cloud_notifier_

Definition at line 76 of file sac_inc_ground_removal_standalone.cpp.

ros::Publisher IncGroundRemoval::cloud_publisher_

Definition at line 87 of file sac_inc_ground_removal_standalone.cpp.

message_filters::Subscriber<sensor_msgs::PointCloud2>* IncGroundRemoval::cloud_subscriber_

Definition at line 77 of file sac_inc_ground_removal_standalone.cpp.

double IncGroundRemoval::ground_slope_threshold_

Definition at line 80 of file sac_inc_ground_removal_standalone.cpp.

sample_consensus::PointCloud IncGroundRemoval::laser_cloud_

Definition at line 72 of file sac_inc_ground_removal_standalone.cpp.

std::string IncGroundRemoval::laser_tilt_mount_frame_

Definition at line 85 of file sac_inc_ground_removal_standalone.cpp.

ros::NodeHandle& IncGroundRemoval::node_
protected

Definition at line 67 of file sac_inc_ground_removal_standalone.cpp.

int IncGroundRemoval::planar_refine_

Definition at line 84 of file sac_inc_ground_removal_standalone.cpp.

std::string IncGroundRemoval::robot_footprint_frame_

Definition at line 85 of file sac_inc_ground_removal_standalone.cpp.

double IncGroundRemoval::sac_distance_threshold_

Definition at line 82 of file sac_inc_ground_removal_standalone.cpp.

double IncGroundRemoval::sac_fitting_distance_threshold_

Definition at line 83 of file sac_inc_ground_removal_standalone.cpp.

int IncGroundRemoval::sac_max_iterations_

Definition at line 81 of file sac_inc_ground_removal_standalone.cpp.

int IncGroundRemoval::sac_min_points_per_model_

Definition at line 81 of file sac_inc_ground_removal_standalone.cpp.

tf::TransformListener IncGroundRemoval::tf_

Definition at line 74 of file sac_inc_ground_removal_standalone.cpp.

geometry_msgs::PointStamped IncGroundRemoval::viewpoint_cloud_

Definition at line 75 of file sac_inc_ground_removal_standalone.cpp.

double IncGroundRemoval::z_threshold_

Definition at line 80 of file sac_inc_ground_removal_standalone.cpp.


The documentation for this class was generated from the following file:


semantic_point_annotator
Author(s): Radu Bogdan Rusu
autogenerated on Mon Jun 10 2019 14:29:03