This class processes the point cloud input to find a checkerboard. More...
#include <checkerboard_finder.h>
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. |
This class processes the point cloud input to find a checkerboard.
Definition at line 37 of file checkerboard_finder.h.
Definition at line 31 of file checkerboard_finder.cpp.
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.
msg | CalibrationData instance to fill in with point information. |
points_x | Number of checkerboard points in x |
points_y | Number of checkerboard points in y |
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.
bool robot_calibration::CheckerboardFinder::waitForCloud | ( | ) | [private] |
Definition at line 76 of file checkerboard_finder.cpp.
std::string robot_calibration::CheckerboardFinder::camera_sensor_name_ [private] |
Should we output debug image/cloud?
Definition at line 74 of file checkerboard_finder.h.
std::string robot_calibration::CheckerboardFinder::chain_sensor_name_ [private] |
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.
bool robot_calibration::CheckerboardFinder::output_debug_ [private] |
Size of a square on checkboard (in meters)
Definition at line 72 of file checkerboard_finder.h.
int robot_calibration::CheckerboardFinder::points_x_ [private] |
Definition at line 67 of file checkerboard_finder.h.
int robot_calibration::CheckerboardFinder::points_y_ [private] |
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.
double robot_calibration::CheckerboardFinder::square_size_ [private] |
Size of checkerboard.
Definition at line 70 of file checkerboard_finder.h.
Definition at line 57 of file checkerboard_finder.h.
bool robot_calibration::CheckerboardFinder::waiting_ [private] |
Outgoing sensor_msgs::PointCloud2.
Definition at line 60 of file checkerboard_finder.h.