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> 43 bool find(robot_calibration_msgs::CalibrationData * msg);
46 bool findInternal(robot_calibration_msgs::CalibrationData * msg);
76 #endif // ROBOT_CALIBRATION_CAPTURE_CHECKERBOARD_FINDER_H bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called...
sensor_msgs::PointCloud2 cloud_
void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
Base class for a feature finder.
ros::Publisher publisher_
Incoming sensor_msgs::PointCloud2.
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
This class processes the point cloud input to find a checkerboard.
double square_size_
Size of checkerboard.
std::string camera_sensor_name_
Name of checkerboard frame.
std::string frame_id_
Should we output debug image/cloud?
bool output_debug_
Size of a square on checkboard (in meters)
std::string chain_sensor_name_
Calibration code lives under this namespace.
bool waiting_
Outgoing sensor_msgs::PointCloud2.
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
ros::Subscriber subscriber_
int points_y_
Size of checkerboard.
Base class for a feature finder.
DepthCameraInfoManager depth_camera_manager_