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

#include <plane_finder.h>

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

Public Member Functions

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

Private Member Functions

void cameraCallback (const sensor_msgs::PointCloud2 &cloud)
 
bool waitForCloud ()
 

Private Attributes

std::string camera_sensor_name_
 
sensor_msgs::PointCloud2 cloud_
 
DepthCameraInfoManager depth_camera_manager_
 
double max_x_
 
double max_y_
 
double max_z_
 
double min_x_
 
double min_y_
 
double min_z_
 
bool output_debug_
 
double points_max_
 
ros::Publisher publisher_
 
ros::Subscriber subscriber_
 
tf2_ros::Buffer tfBuffer_
 
tf2_ros::TransformListener tfListener_
 
std::string transform_frame_
 
bool waiting_
 

Detailed Description

Definition at line 30 of file plane_finder.h.

Constructor & Destructor Documentation

robot_calibration::PlaneFinder::PlaneFinder ( )

Definition at line 36 of file plane_finder.cpp.

Member Function Documentation

void robot_calibration::PlaneFinder::cameraCallback ( const sensor_msgs::PointCloud2 &  cloud)
private

Definition at line 89 of file plane_finder.cpp.

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.

Definition at line 118 of file plane_finder.cpp.

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.

Definition at line 41 of file plane_finder.cpp.

bool robot_calibration::PlaneFinder::waitForCloud ( )
private

Definition at line 98 of file plane_finder.cpp.

Member Data Documentation

std::string robot_calibration::PlaneFinder::camera_sensor_name_
private

Definition at line 51 of file plane_finder.h.

sensor_msgs::PointCloud2 robot_calibration::PlaneFinder::cloud_
private

Definition at line 48 of file plane_finder.h.

DepthCameraInfoManager robot_calibration::PlaneFinder::depth_camera_manager_
private

Definition at line 49 of file plane_finder.h.

double robot_calibration::PlaneFinder::max_x_
private

Definition at line 54 of file plane_finder.h.

double robot_calibration::PlaneFinder::max_y_
private

Definition at line 56 of file plane_finder.h.

double robot_calibration::PlaneFinder::max_z_
private

Definition at line 58 of file plane_finder.h.

double robot_calibration::PlaneFinder::min_x_
private

Definition at line 53 of file plane_finder.h.

double robot_calibration::PlaneFinder::min_y_
private

Definition at line 55 of file plane_finder.h.

double robot_calibration::PlaneFinder::min_z_
private

Definition at line 57 of file plane_finder.h.

bool robot_calibration::PlaneFinder::output_debug_
private

Definition at line 61 of file plane_finder.h.

double robot_calibration::PlaneFinder::points_max_
private

Definition at line 52 of file plane_finder.h.

ros::Publisher robot_calibration::PlaneFinder::publisher_
private

Definition at line 42 of file plane_finder.h.

ros::Subscriber robot_calibration::PlaneFinder::subscriber_
private

Definition at line 41 of file plane_finder.h.

tf2_ros::Buffer robot_calibration::PlaneFinder::tfBuffer_
private

Definition at line 44 of file plane_finder.h.

tf2_ros::TransformListener robot_calibration::PlaneFinder::tfListener_
private

Definition at line 45 of file plane_finder.h.

std::string robot_calibration::PlaneFinder::transform_frame_
private

Definition at line 59 of file plane_finder.h.

bool robot_calibration::PlaneFinder::waiting_
private

Definition at line 47 of file plane_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30