Public Member Functions | Private Member Functions | Private Attributes
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]

List of all members.

Public Member Functions

 CheckerboardFinder (ros::NodeHandle &n)
bool find (robot_calibration_msgs::CalibrationData *msg)
 Attempts to find the checkerboard incoming data.

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_
 Should we output debug image/cloud?
std::string chain_sensor_name_
sensor_msgs::PointCloud2 cloud_
DepthCameraInfoManager depth_camera_manager_
bool output_debug_
 Size of a square on checkboard (in meters)
int points_x_
int points_y_
 Size of checkerboard.
ros::Publisher publisher_
 Incoming sensor_msgs::PointCloud2.
double square_size_
 Size of checkerboard.
ros::Subscriber subscriber_
bool waiting_
 Outgoing sensor_msgs::PointCloud2.

Detailed Description

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

Definition at line 37 of file checkerboard_finder.h.


Constructor & Destructor Documentation

Definition at line 31 of file checkerboard_finder.cpp.


Member Function Documentation

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

Definition at line 66 of file checkerboard_finder.cpp.

bool robot_calibration::CheckerboardFinder::find ( robot_calibration_msgs::CalibrationData *  msg) [virtual]

Attempts to find the checkerboard incoming data.

Parameters:
msgCalibrationData instance to fill in with point information.
points_xNumber of checkerboard points in x
points_yNumber of checkerboard points in y
Returns:
True if point has been filled in.

Implements robot_calibration::FeatureFinder.

Definition at line 97 of file checkerboard_finder.cpp.

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

Definition at line 113 of file checkerboard_finder.cpp.

Definition at line 76 of file checkerboard_finder.cpp.


Member Data Documentation

Should we output debug image/cloud?

Definition at line 74 of file checkerboard_finder.h.

Definition at line 75 of file checkerboard_finder.h.

sensor_msgs::PointCloud2 robot_calibration::CheckerboardFinder::cloud_ [private]

Definition at line 61 of file checkerboard_finder.h.

Definition at line 62 of file checkerboard_finder.h.

Size of a square on checkboard (in meters)

Definition at line 72 of file checkerboard_finder.h.

Definition at line 67 of file checkerboard_finder.h.

Size of checkerboard.

Definition at line 68 of file checkerboard_finder.h.

Incoming sensor_msgs::PointCloud2.

Definition at line 58 of file checkerboard_finder.h.

Size of checkerboard.

Definition at line 70 of file checkerboard_finder.h.

Definition at line 57 of file checkerboard_finder.h.

Outgoing sensor_msgs::PointCloud2.

Definition at line 60 of file checkerboard_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Sat May 20 2017 02:35:31