Go to the documentation of this file.
21 #ifndef ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
22 #define ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
27 #include <robot_calibration_msgs/CalibrationData.h>
29 #include <opencv2/calib3d/calib3d.hpp>
44 bool find(robot_calibration_msgs::CalibrationData * msg);
47 bool findInternal(robot_calibration_msgs::CalibrationData * msg);
49 std::vector<cv::Point2f>& points);
79 #endif // ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
int points_y_
Size of checkerboard.
Base class for a feature finder.
Base class for a feature finder.
std::string camera_sensor_name_
Name of checkerboard frame.
ros::Subscriber subscriber_
bool waiting_
Outgoing sensor_msgs::PointCloud2.
void cameraCallback(const T &msg)
Finds checkerboards in images or point clouds.
bool findCheckerboardPoints(const sensor_msgs::ImagePtr &msg, std::vector< cv::Point2f > &points)
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called....
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
bool output_debug_
Size of a square on checkboard (in meters)
double square_size_
Size of checkerboard.
Calibration code lives under this namespace.
ros::Publisher publisher_
Incoming message.
DepthCameraInfoManager depth_camera_manager_
std::string chain_sensor_name_
std::string frame_id_
Should we output debug image/cloud?
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01