Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
robot_calibration::PlaneFinder Class Reference

Finds the largest plane in a point cloud. More...

#include <plane_finder.h>

Inheritance diagram for robot_calibration::PlaneFinder:
Inheritance graph
[legend]

Public Member Functions

virtual bool find (robot_calibration_msgs::CalibrationData *msg)
 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. More...
 
virtual bool init (const std::string &name, ros::NodeHandle &n)
 Initialize the feature finder. More...
 
 PlaneFinder ()
 
virtual ~PlaneFinder ()=default
 
- Public Member Functions inherited from robot_calibration::FeatureFinder
 FeatureFinder ()
 
std::string getName ()
 Get the name of this feature finder. More...
 
virtual ~FeatureFinder ()
 

Protected Member Functions

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...
 

Protected Attributes

sensor_msgs::PointCloud2 cloud_
 
double cos_normal_angle_
 
DepthCameraInfoManager depth_camera_manager_
 
Eigen::Vector3d desired_normal_
 
double initial_sampling_distance_
 
double max_x_
 
double max_y_
 
double max_z_
 
double min_x_
 
double min_y_
 
double min_z_
 
bool output_debug_
 
std::string plane_sensor_name_
 
double plane_tolerance_
 
int points_max_
 
ros::Publisher publisher_
 
int ransac_iterations_
 
int ransac_points_
 
ros::Subscriber subscriber_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 
std::string transform_frame_
 
bool waiting_
 

Detailed Description

Finds the largest plane in a point cloud.

Definition at line 34 of file plane_finder.h.

Constructor & Destructor Documentation

◆ PlaneFinder()

robot_calibration::PlaneFinder::PlaneFinder ( )

Definition at line 91 of file plane_finder.cpp.

◆ ~PlaneFinder()

virtual robot_calibration::PlaneFinder::~PlaneFinder ( )
virtualdefault

Member Function Documentation

◆ 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_nameUsed to fill in observation "sensor_name"
cloudPoint cloud from which to extract observations
msgCalibrationData to fill with observation
publisherOptional 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
msgThe 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

Initialize the feature finder.

Parameters
nameThe name of this finder.
nhThe nodehandle to use when loading feature finder configuration data.
Returns
True/False if the feature finder was able to be initialized

Reimplemented from robot_calibration::FeatureFinder.

Reimplemented in robot_calibration::RobotFinder.

Definition at line 96 of file plane_finder.cpp.

◆ 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
cloudThe 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

Wait until a new cloud has arrived.

Definition at line 174 of file plane_finder.cpp.

Member Data Documentation

◆ cloud_

sensor_msgs::PointCloud2 robot_calibration::PlaneFinder::cloud_
protected

Definition at line 92 of file plane_finder.h.

◆ cos_normal_angle_

double robot_calibration::PlaneFinder::cos_normal_angle_
protected

Definition at line 104 of file plane_finder.h.

◆ depth_camera_manager_

DepthCameraInfoManager robot_calibration::PlaneFinder::depth_camera_manager_
protected

Definition at line 93 of file plane_finder.h.

◆ desired_normal_

Eigen::Vector3d robot_calibration::PlaneFinder::desired_normal_
protected

Definition at line 103 of file plane_finder.h.

◆ initial_sampling_distance_

double robot_calibration::PlaneFinder::initial_sampling_distance_
protected

Definition at line 98 of file plane_finder.h.

◆ max_x_

double robot_calibration::PlaneFinder::max_x_
protected

Definition at line 100 of file plane_finder.h.

◆ max_y_

double robot_calibration::PlaneFinder::max_y_
protected

Definition at line 101 of file plane_finder.h.

◆ max_z_

double robot_calibration::PlaneFinder::max_z_
protected

Definition at line 102 of file plane_finder.h.

◆ min_x_

double robot_calibration::PlaneFinder::min_x_
protected

Definition at line 100 of file plane_finder.h.

◆ min_y_

double robot_calibration::PlaneFinder::min_y_
protected

Definition at line 101 of file plane_finder.h.

◆ min_z_

double robot_calibration::PlaneFinder::min_z_
protected

Definition at line 102 of file plane_finder.h.

◆ output_debug_

bool robot_calibration::PlaneFinder::output_debug_
protected

Definition at line 109 of file plane_finder.h.

◆ plane_sensor_name_

std::string robot_calibration::PlaneFinder::plane_sensor_name_
protected

Definition at line 96 of file plane_finder.h.

◆ plane_tolerance_

double robot_calibration::PlaneFinder::plane_tolerance_
protected

Definition at line 99 of file plane_finder.h.

◆ points_max_

int robot_calibration::PlaneFinder::points_max_
protected

Definition at line 97 of file plane_finder.h.

◆ publisher_

ros::Publisher robot_calibration::PlaneFinder::publisher_
protected

Definition at line 86 of file plane_finder.h.

◆ ransac_iterations_

int robot_calibration::PlaneFinder::ransac_iterations_
protected

Definition at line 106 of file plane_finder.h.

◆ ransac_points_

int robot_calibration::PlaneFinder::ransac_points_
protected

Definition at line 107 of file plane_finder.h.

◆ subscriber_

ros::Subscriber robot_calibration::PlaneFinder::subscriber_
protected

Definition at line 85 of file plane_finder.h.

◆ tf_buffer_

tf2_ros::Buffer robot_calibration::PlaneFinder::tf_buffer_
protected

Definition at line 88 of file plane_finder.h.

◆ tf_listener_

tf2_ros::TransformListener robot_calibration::PlaneFinder::tf_listener_
protected

Definition at line 89 of file plane_finder.h.

◆ transform_frame_

std::string robot_calibration::PlaneFinder::transform_frame_
protected

Definition at line 105 of file plane_finder.h.

◆ waiting_

bool robot_calibration::PlaneFinder::waiting_
protected

Definition at line 91 of file plane_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01