Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
visp_hand2eye_calibration::Calibrator Class Reference

#include <calibrator.h>

Public Types

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...
 

Public Member Functions

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

Private Member Functions

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...
 

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

visp_hand2eye_calibration::Calibrator::Calibrator ( )

advertises services and subscribes to topics

Definition at line 148 of file calibrator.cpp.

visp_hand2eye_calibration::Calibrator::~Calibrator ( )

Definition at line 193 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
transcamera->object transformation

Definition at line 63 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 79 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 106 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 139 of file calibrator.cpp.

void visp_hand2eye_calibration::Calibrator::spin ( )

spins the ros node

Definition at line 189 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
transworld->effector transformation

Definition at line 71 of file calibrator.cpp.

Member Data Documentation

ros::Subscriber visp_hand2eye_calibration::Calibrator::camera_object_subscriber_
private

Definition at line 73 of file calibrator.h.

image_proc::AdvertisementChecker visp_hand2eye_calibration::Calibrator::check_inputs_
private

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.

ros::ServiceServer visp_hand2eye_calibration::Calibrator::compute_effector_camera_quick_service_
private

Definition at line 71 of file calibrator.h.

ros::ServiceServer visp_hand2eye_calibration::Calibrator::compute_effector_camera_service_
private

Definition at line 70 of file calibrator.h.

ros::NodeHandle visp_hand2eye_calibration::Calibrator::n_
private

Definition at line 79 of file calibrator.h.

unsigned int visp_hand2eye_calibration::Calibrator::queue_size_
private

Definition at line 81 of file calibrator.h.

ros::ServiceServer visp_hand2eye_calibration::Calibrator::reset_service_
private

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.

ros::Subscriber visp_hand2eye_calibration::Calibrator::world_effector_subscriber_
private

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 Sat Mar 13 2021 03:20:04