#include <calibrator.h>
|
typedef boost::function< void(const geometry_msgs::Transform::ConstPtr &)> | camera_object_subscriber_callback_t |
| subscriber type declaration for camera->object topic subscriber More...
|
|
typedef 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 More...
|
|
typedef 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 More...
|
|
typedef boost::function< bool(visp_hand2eye_calibration::reset::Request &, visp_hand2eye_calibration::reset::Response &res)> | reset_service_callback_t |
| service type declaration for reset service More...
|
|
typedef boost::function< void(const geometry_msgs::Transform::ConstPtr &trans)> | world_effector_subscriber_t |
| subscriber type declaration for world->effector topic subscriber More...
|
|
|
void | cameraObjectCallback (const geometry_msgs::Transform::ConstPtr &trans) |
| callback corresponding to the camera->object topic. More...
|
|
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. More...
|
|
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. More...
|
|
bool | resetCallback (visp_hand2eye_calibration::reset::Request &req, visp_hand2eye_calibration::reset::Response &res) |
| service reseting the acumulated data More...
|
|
void | worldEffectorCallback (const geometry_msgs::Transform::ConstPtr &trans) |
| callback corresponding to the world->effector topic. More...
|
|
Definition at line 67 of file calibrator.h.
subscriber type declaration for camera->object topic subscriber
Definition at line 137 of file calibrator.h.
service type declaration for quick effector->camera computation service
Definition at line 130 of file calibrator.h.
service type declaration for effector->camera computation service
Definition at line 127 of file calibrator.h.
service type declaration for reset service
Definition at line 133 of file calibrator.h.
subscriber type declaration for world->effector topic subscriber
Definition at line 140 of file calibrator.h.
visp_hand2eye_calibration::Calibrator::Calibrator |
( |
| ) |
|
advertises services and subscribes to topics
Definition at line 139 of file calibrator.cpp.
visp_hand2eye_calibration::Calibrator::~Calibrator |
( |
| ) |
|
void visp_hand2eye_calibration::Calibrator::cameraObjectCallback |
( |
const geometry_msgs::Transform::ConstPtr & |
trans | ) |
|
|
private |
callback corresponding to the camera->object topic.
Adds a geometry_msgs::Transform to the internal queue. A service may compute the calibration on all recieved elements later.
- Parameters
-
trans | camera->object transformation |
Definition at line 59 of file calibrator.cpp.
bool visp_hand2eye_calibration::Calibrator::computeEffectorCameraCallback |
( |
visp_hand2eye_calibration::compute_effector_camera::Request & |
req, |
|
|
visp_hand2eye_calibration::compute_effector_camera::Response & |
res |
|
) |
| |
|
private |
service computing world->effector transformation from accumulated data.
The service expects the number of recorded camera->object transformation to be equal to the number of recorded world->effector transformations. If it is not equal, the service fails.
Definition at line 75 of file calibrator.cpp.
bool visp_hand2eye_calibration::Calibrator::computeEffectorCameraQuickCallback |
( |
visp_hand2eye_calibration::compute_effector_camera_quick::Request & |
req, |
|
|
visp_hand2eye_calibration::compute_effector_camera_quick::Response & |
res |
|
) |
| |
|
private |
service computing world->effector transformation from parameter-passed data.
The service expects the number of recorded camera->object transformation to be equal to the number of recorded world->effector transformations. If it is not equal, the service fails.
Definition at line 99 of file calibrator.cpp.
bool visp_hand2eye_calibration::Calibrator::resetCallback |
( |
visp_hand2eye_calibration::reset::Request & |
req, |
|
|
visp_hand2eye_calibration::reset::Response & |
res |
|
) |
| |
|
private |
void visp_hand2eye_calibration::Calibrator::spin |
( |
| ) |
|
void visp_hand2eye_calibration::Calibrator::worldEffectorCallback |
( |
const geometry_msgs::Transform::ConstPtr & |
trans | ) |
|
|
private |
callback corresponding to the world->effector topic.
Adds a geometry_msgs::Transform to the internal queue. A service may compute the calibration on all recieved elements later.
- Parameters
-
trans | world->effector transformation |
Definition at line 67 of file calibrator.cpp.
ros::Subscriber visp_hand2eye_calibration::Calibrator::camera_object_subscriber_ |
|
private |
std::vector<vpHomogeneousMatrix> visp_hand2eye_calibration::Calibrator::cMo_vec_ |
|
private |
ros::ServiceServer visp_hand2eye_calibration::Calibrator::compute_effector_camera_quick_service_ |
|
private |
ros::ServiceServer visp_hand2eye_calibration::Calibrator::compute_effector_camera_service_ |
|
private |
unsigned int visp_hand2eye_calibration::Calibrator::queue_size_ |
|
private |
std::vector<vpHomogeneousMatrix> visp_hand2eye_calibration::Calibrator::wMe_vec_ |
|
private |
ros::Subscriber visp_hand2eye_calibration::Calibrator::world_effector_subscriber_ |
|
private |
The documentation for this class was generated from the following files: