Public Member Functions | Private Member Functions | Private Attributes | List of all members
CalibrationWrapper Class Reference

TODO. More...

#include <rest_hand_eye_calibration_client.h>

Public Member Functions

 CalibrationWrapper (std::string host, ros::NodeHandle nh)
 

Private Member Functions

void advertiseServices ()
 Advertises the services in the namespace of nh_. More...
 
bool calibSrv (rc_hand_eye_calibration_client::CalibrationRequest &request, rc_hand_eye_calibration_client::CalibrationResponse &response)
 Perform the calibration and return its result. More...
 
void dynamicReconfigureCb (rc_hand_eye_calibration_client::hand_eye_calibrationConfig &config, uint32_t)
 
bool getCalibResultSrv (rc_hand_eye_calibration_client::CalibrationRequest &request, rc_hand_eye_calibration_client::CalibrationResponse &response)
 Service call to get the result. Also returned directly via calibrate. More...
 
void initConfiguration ()
 
bool removeSrv (std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
 Remove calibration so sensor reports as uncalibrated. More...
 
bool resetSrv (std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
 Delete all stored data, e.g., to start over. More...
 
bool saveSrv (std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
 store hand eye calibration on sensor More...
 
bool setSlotSrv (rc_hand_eye_calibration_client::SetCalibrationPoseRequest &request, rc_hand_eye_calibration_client::SetCalibrationPoseResponse &response)
 Save given pose and the pose of the grid indexed by the given request.slot. More...
 

Private Attributes

std::string host_
 
ros::NodeHandle nh_
 
std::string paramsUrl_
 
std::unique_ptr< dynamic_reconfigure::Server< rc_hand_eye_calibration_client::hand_eye_calibrationConfig > > server_
 
std::string servicesUrl_
 
ros::ServiceServer srv_calibrate_
 
ros::ServiceServer srv_get_result_
 
ros::ServiceServer srv_publish_transform_
 
ros::ServiceServer srv_remove_
 
ros::ServiceServer srv_reset_
 
ros::ServiceServer srv_save_
 
ros::ServiceServer srv_set_slot_
 
int timeoutCurl_
 

Detailed Description

TODO.

Definition at line 19 of file rest_hand_eye_calibration_client.h.

Constructor & Destructor Documentation

CalibrationWrapper::CalibrationWrapper ( std::string  host,
ros::NodeHandle  nh 
)

Definition at line 38 of file rest_hand_eye_calibration_client.cc.

Member Function Documentation

void CalibrationWrapper::advertiseServices ( )
private

Advertises the services in the namespace of nh_.

Definition at line 186 of file rest_hand_eye_calibration_client.cc.

bool CalibrationWrapper::calibSrv ( rc_hand_eye_calibration_client::CalibrationRequest &  request,
rc_hand_eye_calibration_client::CalibrationResponse &  response 
)
private

Perform the calibration and return its result.

Does not save persistently. Call saveSrv for that.

Definition at line 128 of file rest_hand_eye_calibration_client.cc.

void CalibrationWrapper::dynamicReconfigureCb ( rc_hand_eye_calibration_client::hand_eye_calibrationConfig &  config,
uint32_t   
)
private

Definition at line 243 of file rest_hand_eye_calibration_client.cc.

bool CalibrationWrapper::getCalibResultSrv ( rc_hand_eye_calibration_client::CalibrationRequest &  request,
rc_hand_eye_calibration_client::CalibrationResponse &  response 
)
private

Service call to get the result. Also returned directly via calibrate.

Definition at line 157 of file rest_hand_eye_calibration_client.cc.

void CalibrationWrapper::initConfiguration ( )
private

Definition at line 203 of file rest_hand_eye_calibration_client.cc.

bool CalibrationWrapper::removeSrv ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
)
private

Remove calibration so sensor reports as uncalibrated.

Definition at line 79 of file rest_hand_eye_calibration_client.cc.

bool CalibrationWrapper::resetSrv ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
)
private

Delete all stored data, e.g., to start over.

Definition at line 65 of file rest_hand_eye_calibration_client.cc.

bool CalibrationWrapper::saveSrv ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
)
private

store hand eye calibration on sensor

Definition at line 49 of file rest_hand_eye_calibration_client.cc.

bool CalibrationWrapper::setSlotSrv ( rc_hand_eye_calibration_client::SetCalibrationPoseRequest &  request,
rc_hand_eye_calibration_client::SetCalibrationPoseResponse &  response 
)
private

Save given pose and the pose of the grid indexed by the given request.slot.

If slot exists, it is overwritten.

Definition at line 93 of file rest_hand_eye_calibration_client.cc.

Member Data Documentation

std::string CalibrationWrapper::host_
private

Definition at line 73 of file rest_hand_eye_calibration_client.h.

ros::NodeHandle CalibrationWrapper::nh_
private

Definition at line 62 of file rest_hand_eye_calibration_client.h.

std::string CalibrationWrapper::paramsUrl_
private

Definition at line 73 of file rest_hand_eye_calibration_client.h.

std::unique_ptr<dynamic_reconfigure::Server<rc_hand_eye_calibration_client::hand_eye_calibrationConfig> > CalibrationWrapper::server_
private

Definition at line 70 of file rest_hand_eye_calibration_client.h.

std::string CalibrationWrapper::servicesUrl_
private

Definition at line 73 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_calibrate_
private

Definition at line 65 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_get_result_
private

Definition at line 69 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_publish_transform_
private

Definition at line 68 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_remove_
private

Definition at line 67 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_reset_
private

Definition at line 66 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_save_
private

Definition at line 64 of file rest_hand_eye_calibration_client.h.

ros::ServiceServer CalibrationWrapper::srv_set_slot_
private

Definition at line 63 of file rest_hand_eye_calibration_client.h.

int CalibrationWrapper::timeoutCurl_
private

Definition at line 74 of file rest_hand_eye_calibration_client.h.


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


rc_hand_eye_calibration_client
Author(s): Christian Emmerich
autogenerated on Wed Mar 20 2019 07:55:45