Finds the largest plane in a point cloud.
More...
#include <plane_finder.h>
|
virtual void | cameraCallback (const sensor_msgs::PointCloud2 &cloud) |
| ROS callback - updates cloud_ and resets waiting_ to false. More...
|
|
virtual void | extractObservation (const std::string &sensor_name, const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg, ros::Publisher *publisher) |
| Extract points from a cloud into a calibration message. More...
|
|
virtual sensor_msgs::PointCloud2 | extractPlane (sensor_msgs::PointCloud2 &cloud) |
| Extract a plane from the point cloud. More...
|
|
virtual void | removeInvalidPoints (sensor_msgs::PointCloud2 &cloud, double min_x, double max_x, double min_y, double max_y, double min_z, double max_z) |
| Remove invalid points from a cloud. More...
|
|
virtual bool | waitForCloud () |
| Wait until a new cloud has arrived. More...
|
|
Finds the largest plane in a point cloud.
Definition at line 34 of file plane_finder.h.
◆ PlaneFinder()
robot_calibration::PlaneFinder::PlaneFinder |
( |
| ) |
|
◆ ~PlaneFinder()
virtual robot_calibration::PlaneFinder::~PlaneFinder |
( |
| ) |
|
|
virtualdefault |
◆ cameraCallback()
void robot_calibration::PlaneFinder::cameraCallback |
( |
const sensor_msgs::PointCloud2 & |
cloud | ) |
|
|
protectedvirtual |
ROS callback - updates cloud_ and resets waiting_ to false.
Definition at line 165 of file plane_finder.cpp.
◆ extractObservation()
void robot_calibration::PlaneFinder::extractObservation |
( |
const std::string & |
sensor_name, |
|
|
const sensor_msgs::PointCloud2 & |
cloud, |
|
|
robot_calibration_msgs::CalibrationData * |
msg, |
|
|
ros::Publisher * |
publisher |
|
) |
| |
|
protectedvirtual |
Extract points from a cloud into a calibration message.
- Parameters
-
sensor_name | Used to fill in observation "sensor_name" |
cloud | Point cloud from which to extract observations |
msg | CalibrationData to fill with observation |
publisher | Optional pointer to publish the observations as a cloud |
Definition at line 424 of file plane_finder.cpp.
◆ extractPlane()
sensor_msgs::PointCloud2 robot_calibration::PlaneFinder::extractPlane |
( |
sensor_msgs::PointCloud2 & |
cloud | ) |
|
|
protectedvirtual |
Extract a plane from the point cloud.
cloud The cloud to extract plane from - non-plane points will remain
- Returns
- New point cloud comprising only the points in the plane
Definition at line 280 of file plane_finder.cpp.
◆ find()
bool robot_calibration::PlaneFinder::find |
( |
robot_calibration_msgs::CalibrationData * |
msg | ) |
|
|
virtual |
Once the robot has been moved into the proper position and settled, this function will be called. It should add any new observations to the msg passed in.
- Parameters
-
msg | The message to which observations should be added. |
- Returns
- True if feature finder succeeded in finding the features and adding them to the observation list. False otherwise.
Implements robot_calibration::FeatureFinder.
Reimplemented in robot_calibration::RobotFinder.
Definition at line 194 of file plane_finder.cpp.
◆ init()
bool robot_calibration::PlaneFinder::init |
( |
const std::string & |
name, |
|
|
ros::NodeHandle & |
nh |
|
) |
| |
|
virtual |
◆ removeInvalidPoints()
void robot_calibration::PlaneFinder::removeInvalidPoints |
( |
sensor_msgs::PointCloud2 & |
cloud, |
|
|
double |
min_x, |
|
|
double |
max_x, |
|
|
double |
min_y, |
|
|
double |
max_y, |
|
|
double |
min_z, |
|
|
double |
max_z |
|
) |
| |
|
protectedvirtual |
Remove invalid points from a cloud.
- Parameters
-
cloud | The point cloud to remove invalid points from |
Invalid points include:
- points with NAN values
- points with infinite values
- points with z-distance of 0
- points outside our min/max x,y,z parameters
Definition at line 210 of file plane_finder.cpp.
◆ waitForCloud()
bool robot_calibration::PlaneFinder::waitForCloud |
( |
| ) |
|
|
protectedvirtual |
◆ cloud_
sensor_msgs::PointCloud2 robot_calibration::PlaneFinder::cloud_ |
|
protected |
◆ cos_normal_angle_
double robot_calibration::PlaneFinder::cos_normal_angle_ |
|
protected |
◆ depth_camera_manager_
◆ desired_normal_
◆ initial_sampling_distance_
double robot_calibration::PlaneFinder::initial_sampling_distance_ |
|
protected |
◆ max_x_
double robot_calibration::PlaneFinder::max_x_ |
|
protected |
◆ max_y_
double robot_calibration::PlaneFinder::max_y_ |
|
protected |
◆ max_z_
double robot_calibration::PlaneFinder::max_z_ |
|
protected |
◆ min_x_
double robot_calibration::PlaneFinder::min_x_ |
|
protected |
◆ min_y_
double robot_calibration::PlaneFinder::min_y_ |
|
protected |
◆ min_z_
double robot_calibration::PlaneFinder::min_z_ |
|
protected |
◆ output_debug_
bool robot_calibration::PlaneFinder::output_debug_ |
|
protected |
◆ plane_sensor_name_
std::string robot_calibration::PlaneFinder::plane_sensor_name_ |
|
protected |
◆ plane_tolerance_
double robot_calibration::PlaneFinder::plane_tolerance_ |
|
protected |
◆ points_max_
int robot_calibration::PlaneFinder::points_max_ |
|
protected |
◆ publisher_
◆ ransac_iterations_
int robot_calibration::PlaneFinder::ransac_iterations_ |
|
protected |
◆ ransac_points_
int robot_calibration::PlaneFinder::ransac_points_ |
|
protected |
◆ subscriber_
◆ tf_buffer_
◆ tf_listener_
◆ transform_frame_
std::string robot_calibration::PlaneFinder::transform_frame_ |
|
protected |
◆ waiting_
bool robot_calibration::PlaneFinder::waiting_ |
|
protected |
The documentation for this class was generated from the following files: