Go to the documentation of this file.
50 #ifndef __visp_hand2eye_calibration_CALIBRATOR_H__
51 #define __visp_hand2eye_calibration_CALIBRATOR_H__
54 #include "geometry_msgs/Transform.h"
55 #include "visp_hand2eye_calibration/TransformArray.h"
56 #include "visp_hand2eye_calibration/compute_effector_camera_quick.h"
57 #include "visp_hand2eye_calibration/compute_effector_camera.h"
58 #include "visp_hand2eye_calibration/reset.h"
63 class vpHomogeneousMatrix;
108 visp_hand2eye_calibration::compute_effector_camera::Response &res );
118 visp_hand2eye_calibration::compute_effector_camera_quick::Response &res );
122 bool resetCallback(visp_hand2eye_calibration::reset::Request &req,
123 visp_hand2eye_calibration::reset::Response &res );
126 typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera::Request&,visp_hand2eye_calibration::compute_effector_camera::Response& res)>
129 typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera_quick::Request&,visp_hand2eye_calibration::compute_effector_camera_quick::Response& res)>
132 typedef boost::function<bool (visp_hand2eye_calibration::reset::Request&,visp_hand2eye_calibration::reset::Response& res)>
136 typedef boost::function<void (
const geometry_msgs::Transform::ConstPtr& )>
139 typedef boost::function<void (
const geometry_msgs::Transform::ConstPtr& trans)>
void spin()
spins the ros node
std::vector< vpHomogeneousMatrix > wMe_vec_
void worldEffectorCallback(const geometry_msgs::Transform::ConstPtr &trans)
callback corresponding to the world->effector topic.
std::vector< vpHomogeneousMatrix > cMo_vec_
bool resetCallback(visp_hand2eye_calibration::reset::Request &req, visp_hand2eye_calibration::reset::Response &res)
service reseting the acumulated data
ros::ServiceServer compute_effector_camera_service_
ros::ServiceServer reset_service_
image_proc::AdvertisementChecker check_inputs_
Calibrator()
advertises services and subscribes to topics
void cameraObjectCallback(const geometry_msgs::Transform::ConstPtr &trans)
callback corresponding to the camera->object topic.
boost::function< void(const geometry_msgs::Transform::ConstPtr &)> camera_object_subscriber_callback_t
subscriber type declaration for camera->object topic subscriber
ros::Subscriber world_effector_subscriber_
boost::function< void(const geometry_msgs::Transform::ConstPtr &trans)> world_effector_subscriber_t
subscriber type declaration for world->effector topic subscriber
boost::function< bool(visp_hand2eye_calibration::compute_effector_camera::Request &, visp_hand2eye_calibration::compute_effector_camera::Response &res)> compute_effector_camera_service_callback_t
service type declaration for effector->camera computation service
boost::function< bool(visp_hand2eye_calibration::compute_effector_camera_quick::Request &, visp_hand2eye_calibration::compute_effector_camera_quick::Response &res)> compute_effector_camera_quick_service_callback_t
service type declaration for quick effector->camera computation service
boost::function< bool(visp_hand2eye_calibration::reset::Request &, visp_hand2eye_calibration::reset::Response &res)> reset_service_callback_t
service type declaration for reset service
bool computeEffectorCameraCallback(visp_hand2eye_calibration::compute_effector_camera::Request &req, visp_hand2eye_calibration::compute_effector_camera::Response &res)
service computing world->effector transformation from accumulated data.
ros::ServiceServer compute_effector_camera_quick_service_
ros::Subscriber camera_object_subscriber_
bool computeEffectorCameraQuickCallback(visp_hand2eye_calibration::compute_effector_camera_quick::Request &req, visp_hand2eye_calibration::compute_effector_camera_quick::Response &res)
service computing world->effector transformation from parameter-passed data.