| Public Member Functions | |
| void | cloud_cb (const sample_consensus::PointCloud::ConstPtr &msg) | 
| void | computeCentroid (const sample_consensus::PointCloud &points, const std::vector< int > &indices, pcl::PointXYZ ¢roid) | 
| Compute the centroid of a set of points using their indices and return it as a Point32 message. | |
| void | computeCovarianceMatrix (const sample_consensus::PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, pcl::PointXYZ ¢roid) | 
| Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| void | updateParametersFromServer () | 
| virtual | ~IncGroundRemoval () | 
| Public Attributes | |
| sample_consensus::PointCloud | cloud_ | 
| sample_consensus::PointCloud | cloud_noground_ | 
| tf::MessageFilter < sample_consensus::PointCloud > * | cloud_notifier_ | 
| ros::Publisher | cloud_publisher_ | 
| message_filters::Subscriber < sample_consensus::PointCloud > * | 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::NodeHandle & | node_ | 
Definition at line 64 of file sac_inc_ground_removal_standalone.cpp.
| IncGroundRemoval::IncGroundRemoval | ( | ros::NodeHandle & | anode | ) |  [inline] | 
Definition at line 90 of file sac_inc_ground_removal_standalone.cpp.
| virtual IncGroundRemoval::~IncGroundRemoval | ( | ) |  [inline, virtual] | 
Definition at line 133 of file sac_inc_ground_removal_standalone.cpp.
| void IncGroundRemoval::cloud_cb | ( | const sample_consensus::PointCloud::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.
| points | the input point cloud | 
| indices | the point cloud indices that need to be used | 
| centroid | the 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.
| points | the input point cloud | 
| indices | the point cloud indices that need to be used | 
| covariance_matrix | the 3x3 covariance matrix | 
| centroid | the 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.
| points | the input point cloud | 
| indices | the point cloud indices that need to be used | 
| plane_parameters | the plane parameters as: a, b, c, d (ax + by + cz + d = 0) | 
| curvature | the estimated surface curvature as a measure of 
 | 
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.
| points | the point cloud message | 
| indices | a pointer to a set of point cloud indices to test | 
| inliers | the 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.
| normal | the plane normal to be flipped | 
| point | a given point | 
| viewpoint | the 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.
| cloud_frame | the point cloud message TF frame | 
| viewpoint_cloud | the resultant view point in the incoming cloud frame | 
| tf | a pointer to a TransformListener object | 
Definition at line 459 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.
| p | a point | 
| plane_coefficients | the normalized coefficients (a, b, c, d) of a plane | 
Definition at line 447 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.
| val | the value to transform | 
| src_frame | the source frame to transform the value from | 
| tgt_frame | the target frame to transform the value into | 
| stamp | a given time stamp | 
| tf | a pointer to a TransformListener object | 
Definition at line 527 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.
| tf | a pointer to a TransformListener object | 
| target_frame | the target frame to transform the point into | 
| stamped_in | the input point | 
| stamped_out | the output point | 
Definition at line 493 of file sac_inc_ground_removal_standalone.cpp.
| void IncGroundRemoval::updateParametersFromServer | ( | ) |  [inline] | 
Definition at line 137 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 72 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 72 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 76 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 87 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 77 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 80 of file sac_inc_ground_removal_standalone.cpp.
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.
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.
Definition at line 82 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 83 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 81 of file sac_inc_ground_removal_standalone.cpp.
Definition at line 81 of file sac_inc_ground_removal_standalone.cpp.
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.
Definition at line 80 of file sac_inc_ground_removal_standalone.cpp.