#include <calibrator.h>
Public Types | |
typedef boost::function< bool(visp_camera_calibration::calibrate::Request &, visp_camera_calibration::calibrate::Response &res)> | calibrate_service_callback_t |
service type declaration for calibrate service | |
typedef boost::function< void(const visp_camera_calibration::CalibPointArray::ConstPtr &)> | point_correspondence_subscriber_callback_t |
subscriber type declaration for raw_image topic subscriber | |
Public Member Functions | |
Calibrator () | |
void | spin () |
virtual | ~Calibrator () |
Private Member Functions | |
bool | calibrateCallback (visp_camera_calibration::calibrate::Request &req, visp_camera_calibration::calibrate::Response &res) |
service performing the calibration from all previously computed calibration objects. | |
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. | |
Private Attributes | |
ros::ServiceServer | calibrate_service_ |
std::vector< vpCalibration > | calibrations_ |
std::vector< vpPoint > | model_points_ |
ros::NodeHandle | n_ |
ros::Subscriber | point_correspondence_subscriber_ |
unsigned long | queue_size_ |
std::vector< vpPoint > | selected_points_ |
ros::ServiceClient | set_camera_info_bis_service_ |
ros::ServiceClient | set_camera_info_service_ |
Definition at line 62 of file calibrator.h.
typedef boost::function<bool (visp_camera_calibration::calibrate::Request&,visp_camera_calibration::calibrate::Response& res)> visp_camera_calibration::Calibrator::calibrate_service_callback_t |
service type declaration for calibrate service
Definition at line 97 of file calibrator.h.
typedef boost::function<void (const visp_camera_calibration::CalibPointArray::ConstPtr& )> visp_camera_calibration::Calibrator::point_correspondence_subscriber_callback_t |
subscriber type declaration for raw_image topic subscriber
Definition at line 93 of file calibrator.h.
Definition at line 62 of file calibrator.cpp.
visp_camera_calibration::Calibrator::~Calibrator | ( | ) | [virtual] |
Definition at line 154 of file calibrator.cpp.
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.
image_and_points,: | image of the grid and selected keypoints to compute on |
Definition at line 81 of file calibrator.cpp.
Definition at line 150 of file calibrator.cpp.
Definition at line 72 of file calibrator.h.
std::vector<vpCalibration> visp_camera_calibration::Calibrator::calibrations_ [private] |
Definition at line 76 of file calibrator.h.
std::vector<vpPoint> visp_camera_calibration::Calibrator::model_points_ [private] |
Definition at line 75 of file calibrator.h.
Definition at line 65 of file calibrator.h.
Definition at line 69 of file calibrator.h.
unsigned long visp_camera_calibration::Calibrator::queue_size_ [private] |
Definition at line 67 of file calibrator.h.
std::vector<vpPoint> visp_camera_calibration::Calibrator::selected_points_ [private] |
Definition at line 74 of file calibrator.h.
Definition at line 71 of file calibrator.h.
Definition at line 70 of file calibrator.h.