52 #include "visp_camera_calibration/CalibPointArray.h" 53 #include <visp/vpPoint.h> 54 #include <visp/vpCalibration.h> 55 #include "visp_camera_calibration/calibrate.h" 58 #ifndef __visp_camera_calibration_CALIBRATOR_H__ 59 #define __visp_camera_calibration_CALIBRATOR_H__ 89 visp_camera_calibration::calibrate::Response &res);
92 typedef boost::function<void (const visp_camera_calibration::CalibPointArray::ConstPtr& )>
96 typedef boost::function<bool (visp_camera_calibration::calibrate::Request&,visp_camera_calibration::calibrate::Response& res)>
ros::Subscriber point_correspondence_subscriber_
ros::ServiceServer calibrate_service_
std::vector< vpCalibration > calibrations_
std::vector< vpPoint > model_points_
unsigned long queue_size_
bool calibrateCallback(visp_camera_calibration::calibrate::Request &req, visp_camera_calibration::calibrate::Response &res)
service performing the calibration from all previously computed calibration objects.
boost::function< bool(visp_camera_calibration::calibrate::Request &, visp_camera_calibration::calibrate::Response &res)> calibrate_service_callback_t
service type declaration for calibrate service
ros::ServiceClient set_camera_info_bis_service_
std::vector< vpPoint > selected_points_
boost::function< void(const visp_camera_calibration::CalibPointArray::ConstPtr &)> point_correspondence_subscriber_callback_t
subscriber type declaration for raw_image topic subscriber
ros::ServiceClient set_camera_info_service_
void pointCorrespondenceCallback(const visp_camera_calibration::CalibPointArray::ConstPtr &point_correspondence)
callback corresponding to the point_correspondence topic. Adds the obtained calibration pairs objects...