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

This class processes the point cloud input to find a checkerboard. More...

#include <checkerboard_finder.h>

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

Public Member Functions

 CheckerboardFinder ()
 
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...
 
- 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 findInternal (robot_calibration_msgs::CalibrationData *msg)
 
bool waitForCloud ()
 

Private Attributes

std::string camera_sensor_name_
 Name of checkerboard frame. More...
 
std::string chain_sensor_name_
 
sensor_msgs::PointCloud2 cloud_
 
DepthCameraInfoManager depth_camera_manager_
 
std::string frame_id_
 Should we output debug image/cloud? More...
 
bool output_debug_
 Size of a square on checkboard (in meters) More...
 
int points_x_
 
int points_y_
 Size of checkerboard. More...
 
ros::Publisher publisher_
 Incoming sensor_msgs::PointCloud2. More...
 
double square_size_
 Size of checkerboard. More...
 
ros::Subscriber subscriber_
 
bool waiting_
 Outgoing sensor_msgs::PointCloud2. More...
 

Detailed Description

This class processes the point cloud input to find a checkerboard.

Definition at line 38 of file checkerboard_finder.h.

Constructor & Destructor Documentation

robot_calibration::CheckerboardFinder::CheckerboardFinder ( )

Definition at line 34 of file checkerboard_finder.cpp.

Member Function Documentation

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

Definition at line 81 of file checkerboard_finder.cpp.

bool robot_calibration::CheckerboardFinder::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 112 of file checkerboard_finder.cpp.

bool robot_calibration::CheckerboardFinder::findInternal ( robot_calibration_msgs::CalibrationData *  msg)
private

Definition at line 128 of file checkerboard_finder.cpp.

bool robot_calibration::CheckerboardFinder::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 39 of file checkerboard_finder.cpp.

bool robot_calibration::CheckerboardFinder::waitForCloud ( )
private

Definition at line 91 of file checkerboard_finder.cpp.

Member Data Documentation

std::string robot_calibration::CheckerboardFinder::camera_sensor_name_
private

Name of checkerboard frame.

Definition at line 70 of file checkerboard_finder.h.

std::string robot_calibration::CheckerboardFinder::chain_sensor_name_
private

Definition at line 71 of file checkerboard_finder.h.

sensor_msgs::PointCloud2 robot_calibration::CheckerboardFinder::cloud_
private

Definition at line 55 of file checkerboard_finder.h.

DepthCameraInfoManager robot_calibration::CheckerboardFinder::depth_camera_manager_
private

Definition at line 56 of file checkerboard_finder.h.

std::string robot_calibration::CheckerboardFinder::frame_id_
private

Should we output debug image/cloud?

Definition at line 68 of file checkerboard_finder.h.

bool robot_calibration::CheckerboardFinder::output_debug_
private

Size of a square on checkboard (in meters)

Definition at line 66 of file checkerboard_finder.h.

int robot_calibration::CheckerboardFinder::points_x_
private

Definition at line 61 of file checkerboard_finder.h.

int robot_calibration::CheckerboardFinder::points_y_
private

Size of checkerboard.

Definition at line 62 of file checkerboard_finder.h.

ros::Publisher robot_calibration::CheckerboardFinder::publisher_
private

Incoming sensor_msgs::PointCloud2.

Definition at line 52 of file checkerboard_finder.h.

double robot_calibration::CheckerboardFinder::square_size_
private

Size of checkerboard.

Definition at line 64 of file checkerboard_finder.h.

ros::Subscriber robot_calibration::CheckerboardFinder::subscriber_
private

Definition at line 51 of file checkerboard_finder.h.

bool robot_calibration::CheckerboardFinder::waiting_
private

Outgoing sensor_msgs::PointCloud2.

Definition at line 54 of file checkerboard_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