Public Types | Public Member Functions | Private Member Functions | Private Attributes
visp_hand2eye_calibration::Calibrator Class Reference

#include <calibrator.h>

List of all members.

Public Types

typedef boost::function< void(const
geometry_msgs::Transform::ConstPtr &)> 
camera_object_subscriber_callback_t
 subscriber type declaration for camera->object topic subscriber
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
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
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
typedef boost::function< void(const
geometry_msgs::Transform::ConstPtr
&trans)> 
world_effector_subscriber_t
 subscriber type declaration for world->effector topic subscriber

Public Member Functions

 Calibrator ()
 advertises services and subscribes to topics
void spin ()
 spins the ros node
 ~Calibrator ()

Private Member Functions

void cameraObjectCallback (const geometry_msgs::Transform::ConstPtr &trans)
 callback corresponding to the camera->object topic.
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.
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.
bool resetCallback (visp_hand2eye_calibration::reset::Request &req, visp_hand2eye_calibration::reset::Response &res)
 service reseting the acumulated data
void worldEffectorCallback (const geometry_msgs::Transform::ConstPtr &trans)
 callback corresponding to the world->effector topic.

Private Attributes

ros::Subscriber camera_object_subscriber_
image_proc::AdvertisementChecker check_inputs_
std::vector< vpHomogeneousMatrix > cMo_vec_
ros::ServiceServer compute_effector_camera_quick_service_
ros::ServiceServer compute_effector_camera_service_
ros::NodeHandle n_
unsigned int queue_size_
ros::ServiceServer reset_service_
std::vector< vpHomogeneousMatrix > wMe_vec_
ros::Subscriber world_effector_subscriber_

Detailed Description

Definition at line 67 of file calibrator.h.


Member Typedef Documentation

typedef boost::function<void (const geometry_msgs::Transform::ConstPtr& )> visp_hand2eye_calibration::Calibrator::camera_object_subscriber_callback_t

subscriber type declaration for camera->object topic subscriber

Definition at line 137 of file calibrator.h.

typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera_quick::Request&,visp_hand2eye_calibration::compute_effector_camera_quick::Response& res)> visp_hand2eye_calibration::Calibrator::compute_effector_camera_quick_service_callback_t

service type declaration for quick effector->camera computation service

Definition at line 130 of file calibrator.h.

typedef boost::function<bool (visp_hand2eye_calibration::compute_effector_camera::Request&,visp_hand2eye_calibration::compute_effector_camera::Response& res)> visp_hand2eye_calibration::Calibrator::compute_effector_camera_service_callback_t

service type declaration for effector->camera computation service

Definition at line 127 of file calibrator.h.

typedef boost::function<bool (visp_hand2eye_calibration::reset::Request&,visp_hand2eye_calibration::reset::Response& res)> visp_hand2eye_calibration::Calibrator::reset_service_callback_t

service type declaration for reset service

Definition at line 133 of file calibrator.h.

typedef boost::function<void (const geometry_msgs::Transform::ConstPtr& trans)> visp_hand2eye_calibration::Calibrator::world_effector_subscriber_t

subscriber type declaration for world->effector topic subscriber

Definition at line 140 of file calibrator.h.


Constructor & Destructor Documentation

advertises services and subscribes to topics

Definition at line 139 of file calibrator.cpp.

Definition at line 184 of file calibrator.cpp.


Member Function Documentation

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]

service reseting the acumulated data

Definition at line 130 of file calibrator.cpp.

spins the ros node

Definition at line 180 of file calibrator.cpp.

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.


Member Data Documentation

Definition at line 73 of file calibrator.h.

Definition at line 75 of file calibrator.h.

std::vector<vpHomogeneousMatrix> visp_hand2eye_calibration::Calibrator::cMo_vec_ [private]

Definition at line 77 of file calibrator.h.

Definition at line 71 of file calibrator.h.

Definition at line 70 of file calibrator.h.

Definition at line 79 of file calibrator.h.

Definition at line 81 of file calibrator.h.

Definition at line 72 of file calibrator.h.

std::vector<vpHomogeneousMatrix> visp_hand2eye_calibration::Calibrator::wMe_vec_ [private]

Definition at line 78 of file calibrator.h.

Definition at line 74 of file calibrator.h.


The documentation for this class was generated from the following files:


visp_hand2eye_calibration
Author(s): Filip Novotny
autogenerated on Fri Aug 28 2015 13:36:35