Public Member Functions | Private Member Functions | Private Attributes | List of all members
robot_calibration::CheckerboardFinder< T > Class Template Reference

Finds checkerboards in images or point clouds. More...

#include <checkerboard_finder.h>

Inheritance diagram for robot_calibration::CheckerboardFinder< T >:
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 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...
 
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...
 

Detailed Description

template<typename T>
class robot_calibration::CheckerboardFinder< T >

Finds checkerboards in images or point clouds.

Definition at line 39 of file checkerboard_finder.h.

Constructor & Destructor Documentation

◆ CheckerboardFinder()

Definition at line 37 of file checkerboard_finder.cpp.

Member Function Documentation

◆ cameraCallback()

template<typename T >
void robot_calibration::CheckerboardFinder< T >::cameraCallback ( const T &  msg)
private

Definition at line 90 of file checkerboard_finder.cpp.

◆ find()

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::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 123 of file checkerboard_finder.cpp.

◆ findCheckerboardPoints()

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::findCheckerboardPoints ( const sensor_msgs::ImagePtr &  msg,
std::vector< cv::Point2f > &  points 
)
private

Definition at line 318 of file checkerboard_finder.cpp.

◆ findInternal() [1/3]

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::findInternal ( robot_calibration_msgs::CalibrationData *  msg)
private

◆ findInternal() [2/3]

bool robot_calibration::CheckerboardFinder< sensor_msgs::PointCloud2 >::findInternal ( robot_calibration_msgs::CalibrationData *  msg)
private

Definition at line 140 of file checkerboard_finder.cpp.

◆ findInternal() [3/3]

bool robot_calibration::CheckerboardFinder< sensor_msgs::ImagePtr >::findInternal ( robot_calibration_msgs::CalibrationData *  msg)
private

Definition at line 257 of file checkerboard_finder.cpp.

◆ init()

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::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 43 of file checkerboard_finder.cpp.

◆ waitForMsg()

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::waitForMsg
private

Definition at line 101 of file checkerboard_finder.cpp.

Member Data Documentation

◆ camera_sensor_name_

template<typename T >
std::string robot_calibration::CheckerboardFinder< T >::camera_sensor_name_
private

Name of checkerboard frame.

Definition at line 73 of file checkerboard_finder.h.

◆ chain_sensor_name_

template<typename T >
std::string robot_calibration::CheckerboardFinder< T >::chain_sensor_name_
private

Definition at line 74 of file checkerboard_finder.h.

◆ depth_camera_manager_

template<typename T >
DepthCameraInfoManager robot_calibration::CheckerboardFinder< T >::depth_camera_manager_
private

Definition at line 59 of file checkerboard_finder.h.

◆ frame_id_

template<typename T >
std::string robot_calibration::CheckerboardFinder< T >::frame_id_
private

Should we output debug image/cloud?

Definition at line 71 of file checkerboard_finder.h.

◆ msg_

template<typename T >
T robot_calibration::CheckerboardFinder< T >::msg_
private

Definition at line 58 of file checkerboard_finder.h.

◆ output_debug_

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::output_debug_
private

Size of a square on checkboard (in meters)

Definition at line 69 of file checkerboard_finder.h.

◆ points_x_

template<typename T >
int robot_calibration::CheckerboardFinder< T >::points_x_
private

Definition at line 64 of file checkerboard_finder.h.

◆ points_y_

template<typename T >
int robot_calibration::CheckerboardFinder< T >::points_y_
private

Size of checkerboard.

Definition at line 65 of file checkerboard_finder.h.

◆ publisher_

template<typename T >
ros::Publisher robot_calibration::CheckerboardFinder< T >::publisher_
private

Incoming message.

Definition at line 55 of file checkerboard_finder.h.

◆ square_size_

template<typename T >
double robot_calibration::CheckerboardFinder< T >::square_size_
private

Size of checkerboard.

Definition at line 67 of file checkerboard_finder.h.

◆ subscriber_

template<typename T >
ros::Subscriber robot_calibration::CheckerboardFinder< T >::subscriber_
private

Definition at line 54 of file checkerboard_finder.h.

◆ waiting_

template<typename T >
bool robot_calibration::CheckerboardFinder< T >::waiting_
private

Outgoing sensor_msgs::PointCloud2.

Definition at line 57 of file checkerboard_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01