Finds checkerboards in images or point clouds. More...
#include <checkerboard_finder.h>
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... | |
![]() | |
FeatureFinder () | |
std::string | getName () |
Get the name of this feature finder. More... | |
virtual | ~FeatureFinder () |
Private Member Functions | |
void | cameraCallback (const T &msg) |
bool | findCheckerboardPoints (const sensor_msgs::ImagePtr &msg, std::vector< cv::Point2f > &points) |
bool | findInternal (robot_calibration_msgs::CalibrationData *msg) |
bool | findInternal (robot_calibration_msgs::CalibrationData *msg) |
bool | findInternal (robot_calibration_msgs::CalibrationData *msg) |
bool | waitForMsg () |
Private Attributes | |
std::string | camera_sensor_name_ |
Name of checkerboard frame. More... | |
std::string | chain_sensor_name_ |
DepthCameraInfoManager | depth_camera_manager_ |
std::string | frame_id_ |
Should we output debug image/cloud? More... | |
T | msg_ |
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 message. More... | |
double | square_size_ |
Size of checkerboard. More... | |
ros::Subscriber | subscriber_ |
bool | waiting_ |
Outgoing sensor_msgs::PointCloud2. More... | |
Finds checkerboards in images or point clouds.
Definition at line 39 of file checkerboard_finder.h.
robot_calibration::CheckerboardFinder< T >::CheckerboardFinder |
Definition at line 37 of file checkerboard_finder.cpp.
|
private |
Definition at line 90 of file checkerboard_finder.cpp.
|
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.
msg | The message to which observations should be added. |
Implements robot_calibration::FeatureFinder.
Definition at line 123 of file checkerboard_finder.cpp.
|
private |
Definition at line 318 of file checkerboard_finder.cpp.
|
private |
|
private |
Definition at line 140 of file checkerboard_finder.cpp.
|
private |
Definition at line 257 of file checkerboard_finder.cpp.
|
virtual |
Initialize the feature finder.
name | The name of this finder. |
nh | The nodehandle to use when loading feature finder configuration data. |
Reimplemented from robot_calibration::FeatureFinder.
Definition at line 43 of file checkerboard_finder.cpp.
|
private |
Definition at line 101 of file checkerboard_finder.cpp.
|
private |
Name of checkerboard frame.
Definition at line 73 of file checkerboard_finder.h.
|
private |
Definition at line 74 of file checkerboard_finder.h.
|
private |
Definition at line 59 of file checkerboard_finder.h.
|
private |
Should we output debug image/cloud?
Definition at line 71 of file checkerboard_finder.h.
|
private |
Definition at line 58 of file checkerboard_finder.h.
|
private |
Size of a square on checkboard (in meters)
Definition at line 69 of file checkerboard_finder.h.
|
private |
Definition at line 64 of file checkerboard_finder.h.
|
private |
Size of checkerboard.
Definition at line 65 of file checkerboard_finder.h.
|
private |
Incoming message.
Definition at line 55 of file checkerboard_finder.h.
|
private |
Size of checkerboard.
Definition at line 67 of file checkerboard_finder.h.
|
private |
Definition at line 54 of file checkerboard_finder.h.
|
private |
Outgoing sensor_msgs::PointCloud2.
Definition at line 57 of file checkerboard_finder.h.