#include <calibrator.h>
|
bool | calibrateCallback (visp_camera_calibration::calibrate::Request &req, visp_camera_calibration::calibrate::Response &res) |
| service performing the calibration from all previously computed calibration objects. More...
|
|
void | pointCorrespondenceCallback (const visp_camera_calibration::CalibPointArray::ConstPtr &point_correspondence) |
| callback corresponding to the point_correspondence topic. Adds the obtained calibration pairs objects to an internal calibration list. More...
|
|
Definition at line 62 of file calibrator.h.
service type declaration for calibrate service
Definition at line 97 of file calibrator.h.
subscriber type declaration for raw_image topic subscriber
Definition at line 93 of file calibrator.h.
visp_camera_calibration::Calibrator::Calibrator |
( |
| ) |
|
visp_camera_calibration::Calibrator::~Calibrator |
( |
| ) |
|
|
virtual |
bool visp_camera_calibration::Calibrator::calibrateCallback |
( |
visp_camera_calibration::calibrate::Request & |
req, |
|
|
visp_camera_calibration::calibrate::Response & |
res |
|
) |
| |
|
private |
service performing the calibration from all previously computed calibration objects.
Definition at line 96 of file calibrator.cpp.
void visp_camera_calibration::Calibrator::pointCorrespondenceCallback |
( |
const visp_camera_calibration::CalibPointArray::ConstPtr & |
point_correspondence | ) |
|
|
private |
callback corresponding to the point_correspondence topic. Adds the obtained calibration pairs objects to an internal calibration list.
- Parameters
-
image_and_points | image of the grid and selected keypoints to compute on |
Definition at line 81 of file calibrator.cpp.
void visp_camera_calibration::Calibrator::spin |
( |
| ) |
|
std::vector<vpCalibration> visp_camera_calibration::Calibrator::calibrations_ |
|
private |
std::vector<vpPoint> visp_camera_calibration::Calibrator::model_points_ |
|
private |
ros::Subscriber visp_camera_calibration::Calibrator::point_correspondence_subscriber_ |
|
private |
unsigned long visp_camera_calibration::Calibrator::queue_size_ |
|
private |
std::vector<vpPoint> visp_camera_calibration::Calibrator::selected_points_ |
|
private |
The documentation for this class was generated from the following files: