Public Member Functions | |
void | cloud_cb (const sensor_msgs::PointCloud::ConstPtr &cloud) |
bool | detect_wall (stereo_wall_detection::DetectWall::Request &req, stereo_wall_detection::DetectWall::Response &resp) |
bool | fitSACPlane (sensor_msgs::PointCloud *points, vector< int > &inliers, vector< double > &coeff, const geometry_msgs::PointStamped &viewpoint_cloud, double dist_thresh) |
Find a plane model in a point cloud with SAmple Consensus methods. | |
PlanarFit () | |
void | publishNormal (const geometry_msgs::Point32 &position, Eigen::Quaternionf orientation, const std_msgs::Header &header, double length) |
Publish the normals as cute little lines : assumes normalized point normals ! | |
virtual | ~PlanarFit () |
Public Attributes | |
sensor_msgs::PointCloud | cloud_msg_ |
boost::mutex | cloud_msg_mutex_ |
string | cloud_topic_ |
int | k_ |
geometry_msgs::Point | leaf_width_ |
double | max_dist_ |
int | normals_fidelity_ |
ros::Publisher | plane_normal_pub_ |
double | radius_ |
bool | received_cloud_ |
double | sac_distance_threshold_ |
double | sac_normal_distance_weight_ |
double | sac_normal_inlier_distance_weight_ |
int | sac_use_normals_ |
ros::ServiceServer | serv_ |
bool | subscriber_enabled_ |
ros::Publisher | vis_pub_ |
Protected Attributes | |
ros::NodeHandle | nh_ |
Definition at line 73 of file wall_extractor.cpp.
PlanarFit::PlanarFit | ( | ) | [inline] |
Definition at line 106 of file wall_extractor.cpp.
virtual PlanarFit::~PlanarFit | ( | ) | [inline, virtual] |
Definition at line 130 of file wall_extractor.cpp.
void PlanarFit::cloud_cb | ( | const sensor_msgs::PointCloud::ConstPtr & | cloud | ) | [inline] |
Definition at line 135 of file wall_extractor.cpp.
bool PlanarFit::detect_wall | ( | stereo_wall_detection::DetectWall::Request & | req, | |
stereo_wall_detection::DetectWall::Response & | resp | |||
) | [inline] |
Definition at line 147 of file wall_extractor.cpp.
bool PlanarFit::fitSACPlane | ( | sensor_msgs::PointCloud * | points, | |
vector< int > & | inliers, | |||
vector< double > & | coeff, | |||
const geometry_msgs::PointStamped & | viewpoint_cloud, | |||
double | dist_thresh | |||
) | [inline] |
Find a plane model in a point cloud with SAmple Consensus methods.
points | the point cloud message | |
inliers | the resultant planar inliers | |
coeff | the resultant plane coefficients | |
viewpoint_cloud | a point to the pose where the data was acquired from (for normal flipping) | |
dist_thresh | the maximum allowed distance threshold of an inlier to the model | |
min_pts | the minimum number of points allowed as inliers for a plane model |
Definition at line 276 of file wall_extractor.cpp.
void PlanarFit::publishNormal | ( | const geometry_msgs::Point32 & | position, | |
Eigen::Quaternionf | orientation, | |||
const std_msgs::Header & | header, | |||
double | length | |||
) | [inline] |
Publish the normals as cute little lines : assumes normalized point normals !
points | pointer to the point cloud message | |
indices | indices of the point cloud normals to publish | |
nx_idx | the index of the x normal | |
ny_idx | the index of the y normal | |
nz_idx | the index of the z normal | |
length | the length of the normal lines | |
width | the width of the normal lines |
Definition at line 328 of file wall_extractor.cpp.
sensor_msgs::PointCloud PlanarFit::cloud_msg_ |
Definition at line 80 of file wall_extractor.cpp.
boost::mutex PlanarFit::cloud_msg_mutex_ |
Definition at line 81 of file wall_extractor.cpp.
string PlanarFit::cloud_topic_ |
Definition at line 102 of file wall_extractor.cpp.
int PlanarFit::k_ |
Definition at line 88 of file wall_extractor.cpp.
geometry_msgs::Point PlanarFit::leaf_width_ |
Definition at line 91 of file wall_extractor.cpp.
double PlanarFit::max_dist_ |
Definition at line 101 of file wall_extractor.cpp.
ros::NodeHandle PlanarFit::nh_ [protected] |
Definition at line 76 of file wall_extractor.cpp.
Definition at line 94 of file wall_extractor.cpp.
ros::Publisher PlanarFit::plane_normal_pub_ |
Definition at line 83 of file wall_extractor.cpp.
double PlanarFit::radius_ |
Definition at line 87 of file wall_extractor.cpp.
Definition at line 103 of file wall_extractor.cpp.
Definition at line 96 of file wall_extractor.cpp.
Definition at line 98 of file wall_extractor.cpp.
Definition at line 99 of file wall_extractor.cpp.
Definition at line 97 of file wall_extractor.cpp.
ros::ServiceServer PlanarFit::serv_ |
Definition at line 82 of file wall_extractor.cpp.
Definition at line 103 of file wall_extractor.cpp.
ros::Publisher PlanarFit::vis_pub_ |
Definition at line 84 of file wall_extractor.cpp.