$search
| Public Member Functions | |
| void | cloud_cb (const sensor_msgs::PointCloudConstPtr &msg) | 
| bool | fitSACLine (sensor_msgs::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 | 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 PointCloud message frame. | |
| GroundRemoval (ros::NodeHandle &anode) | |
| void | splitPointsBasedOnLaserScanIndex (sensor_msgs::PointCloud *points, vector< int > *indices, vector< vector< int > > &clusters, int idx) | 
| Decompose a PointCloud message into LaserScan clusters. | |
| 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< geometry_msgs::Point32 > &stamped_in, tf::Stamped< geometry_msgs::Point32 > &stamped_out) | 
| Transform a given point from its current frame to a given target frame. | |
| void | updateParametersFromServer () | 
| Public Attributes | |
| sensor_msgs::PointCloud | cloud_ | 
| sensor_msgs::PointCloud | cloud_noground_ | 
| ros::Publisher | cloud_publisher_ | 
| ros::Subscriber | cloud_subscriber_ | 
| int | planar_refine_ | 
| double | sac_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 70 of file sac_ground_removal.cpp.
| GroundRemoval::GroundRemoval | ( | ros::NodeHandle & | anode | ) |  [inline] | 
Definition at line 93 of file sac_ground_removal.cpp.
| void GroundRemoval::cloud_cb | ( | const sensor_msgs::PointCloudConstPtr & | msg | ) |  [inline] | 
Definition at line 222 of file sac_ground_removal.cpp.
| bool GroundRemoval::fitSACLine | ( | sensor_msgs::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 183 of file sac_ground_removal.cpp.
| void GroundRemoval::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 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 403 of file sac_ground_removal.cpp.
| void GroundRemoval::splitPointsBasedOnLaserScanIndex | ( | sensor_msgs::PointCloud * | points, | |
| vector< int > * | indices, | |||
| vector< vector< int > > & | clusters, | |||
| int | idx | |||
| ) |  [inline] | 
Decompose a PointCloud message into LaserScan clusters.
| points | pointer to the point cloud message | |
| indices | pointer to a list of point indices | |
| clusters | the resultant clusters | |
| idx | the index of the channel containing the laser scan index | 
Definition at line 138 of file sac_ground_removal.cpp.
| double GroundRemoval::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 467 of file sac_ground_removal.cpp.
| void GroundRemoval::transformPoint | ( | tf::TransformListener * | tf, | |
| const std::string & | target_frame, | |||
| const tf::Stamped< geometry_msgs::Point32 > & | stamped_in, | |||
| tf::Stamped< geometry_msgs::Point32 > & | 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 433 of file sac_ground_removal.cpp.
| void GroundRemoval::updateParametersFromServer | ( | ) |  [inline] | 
Definition at line 124 of file sac_ground_removal.cpp.
Definition at line 78 of file sac_ground_removal.cpp.
Definition at line 78 of file sac_ground_removal.cpp.
Definition at line 89 of file sac_ground_removal.cpp.
Definition at line 90 of file sac_ground_removal.cpp.
| ros::NodeHandle& GroundRemoval::node_  [protected] | 
Definition at line 73 of file sac_ground_removal.cpp.
Definition at line 87 of file sac_ground_removal.cpp.
Definition at line 86 of file sac_ground_removal.cpp.
Definition at line 85 of file sac_ground_removal.cpp.
Definition at line 85 of file sac_ground_removal.cpp.
Definition at line 80 of file sac_ground_removal.cpp.
Definition at line 81 of file sac_ground_removal.cpp.
| double GroundRemoval::z_threshold_ | 
Definition at line 84 of file sac_ground_removal.cpp.