Public Member Functions | Private Member Functions | Private Attributes | List of all members
rc_hand_eye_calibration_client::HandEyeCalibClient Class Reference

#include <rc_hand_eye_calibration_client.h>

Public Member Functions

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

Private Member Functions

void advertiseServices ()
 Advertises the services in the namespace of nh_. More...
 
void calibResponseHandler (CalibrationResponse &res)
 update and broadcast the internally cached calibration result. More...
 
bool calibSrv (rc_hand_eye_calibration_client::CalibrationRequest &req, rc_hand_eye_calibration_client::CalibrationResponse &res)
 Perform the calibration and return its result. More...
 
template<typename Request , typename Response >
bool callService (const std::string &name, const Request &req, Response &res)
 
void dynamicReconfigureCb (rc_hand_eye_calibration_client::hand_eye_calibrationConfig &config, uint32_t)
 
bool getCalibResultSrv (rc_hand_eye_calibration_client::CalibrationRequest &req, rc_hand_eye_calibration_client::CalibrationResponse &res)
 Service call to get the result. Also returned directly via calibrate. More...
 
void initConfiguration ()
 
void initTimers ()
 Initialize timers to periodically publish and/or request the calibration Depends on parameters: calibration_publication_period and calibration_request_period. More...
 
bool removeSrv (rc_hand_eye_calibration_client::TriggerRequest &req, rc_hand_eye_calibration_client::TriggerResponse &res)
 Remove calibration so sensor reports as uncalibrated. More...
 
void requestCalibration (const ros::SteadyTimerEvent &)
 Wraps the above getCalibResultSrv. More...
 
bool resetSrv (rc_hand_eye_calibration_client::TriggerRequest &req, rc_hand_eye_calibration_client::TriggerResponse &res)
 Delete all stored data, e.g., to start over. More...
 
bool saveSrv (rc_hand_eye_calibration_client::TriggerRequest &req, rc_hand_eye_calibration_client::TriggerResponse &res)
 store hand eye calibration on sensor More...
 
void sendCachedCalibration (const ros::SteadyTimerEvent &=ros::SteadyTimerEvent())
 
bool setCalibSrv (rc_hand_eye_calibration_client::SetCalibrationRequest &req, rc_hand_eye_calibration_client::SetCalibrationResponse &res)
 Service call to set the calibration. More...
 
bool setSlotSrv (rc_hand_eye_calibration_client::SetCalibrationPoseRequest &req, rc_hand_eye_calibration_client::SetCalibrationPoseResponse &res)
 Save given pose and the pose of the grid indexed by the given request.slot. More...
 
void updateCalibrationCache (const rc_hand_eye_calibration_client::CalibrationResponse &res)
 Copy resp into current_calibration_. More...
 

Private Attributes

std::string base_frame_id_ = "base_link"
 
double calib_publish_period_ = 0.0
 Whether to send the transformation periodically instead of as a static transformation Zero or negative value: static tf (via latched topic, sends updates on new calibration response) More...
 
ros::SteadyTimer calib_publish_timer_
 
double calib_request_period_ = 0.0
 If non-negative: Periodically update the calibration by requesting it. More...
 
ros::SteadyTimer calib_request_timer_
 
std::string camera_frame_id_ = "camera"
 Default Frame Ids to be used for the tf broadcast. More...
 
geometry_msgs::TransformStamped current_calibration_
 
tf2_ros::TransformBroadcaster dynamic_tf2_broadcaster_
 To be used for periodic sending. More...
 
std::string endeff_frame_id_ = "end_effector"
 Which one is used depends on the value of "robot_mounted" in the calibration response. More...
 
std::tuple< size_t, size_t, size_t > image_version_
 
ros::NodeHandle nh_
 
rc_rest_api::RestHelper rest_helper_
 
std::unique_ptr< dynamic_reconfigure::Server< rc_hand_eye_calibration_client::hand_eye_calibrationConfig > > server_
 
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_calibration_
 
ros::ServiceServer srv_set_slot_
 
tf2_ros::StaticTransformBroadcaster static_tf2_broadcaster_
 To be used for on-change sending only. More...
 

Detailed Description

Definition at line 55 of file rc_hand_eye_calibration_client.h.

Constructor & Destructor Documentation

rc_hand_eye_calibration_client::HandEyeCalibClient::HandEyeCalibClient ( std::string  host,
ros::NodeHandle  nh 
)

Definition at line 45 of file rc_hand_eye_calibration_client.cpp.

Member Function Documentation

void rc_hand_eye_calibration_client::HandEyeCalibClient::advertiseServices ( )
private

Advertises the services in the namespace of nh_.

Definition at line 220 of file rc_hand_eye_calibration_client.cpp.

void rc_hand_eye_calibration_client::HandEyeCalibClient::calibResponseHandler ( CalibrationResponse &  res)
private

update and broadcast the internally cached calibration result.

Definition at line 136 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::calibSrv ( rc_hand_eye_calibration_client::CalibrationRequest &  req,
rc_hand_eye_calibration_client::CalibrationResponse &  res 
)
private

Perform the calibration and return its result.

Does not save persistently. Call saveSrv for that.

Definition at line 154 of file rc_hand_eye_calibration_client.cpp.

template<typename Request , typename Response >
bool rc_hand_eye_calibration_client::HandEyeCalibClient::callService ( const std::string &  name,
const Request &  req,
Response &  res 
)
private

Definition at line 55 of file rc_hand_eye_calibration_client.cpp.

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

Definition at line 293 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::getCalibResultSrv ( rc_hand_eye_calibration_client::CalibrationRequest &  req,
rc_hand_eye_calibration_client::CalibrationResponse &  res 
)
private

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

Definition at line 161 of file rc_hand_eye_calibration_client.cpp.

void rc_hand_eye_calibration_client::HandEyeCalibClient::initConfiguration ( )
private

Definition at line 256 of file rc_hand_eye_calibration_client.cpp.

void rc_hand_eye_calibration_client::HandEyeCalibClient::initTimers ( )
private

Initialize timers to periodically publish and/or request the calibration Depends on parameters: calibration_publication_period and calibration_request_period.

Definition at line 71 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::removeSrv ( rc_hand_eye_calibration_client::TriggerRequest &  req,
rc_hand_eye_calibration_client::TriggerResponse &  res 
)
private

Remove calibration so sensor reports as uncalibrated.

Definition at line 113 of file rc_hand_eye_calibration_client.cpp.

void rc_hand_eye_calibration_client::HandEyeCalibClient::requestCalibration ( const ros::SteadyTimerEvent )
private

Wraps the above getCalibResultSrv.

Called by calib_request_timer_ for the side effect of updating and broadcasting the cached calibration via tf.

Definition at line 183 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::resetSrv ( rc_hand_eye_calibration_client::TriggerRequest &  req,
rc_hand_eye_calibration_client::TriggerResponse &  res 
)
private

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

Definition at line 107 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::saveSrv ( rc_hand_eye_calibration_client::TriggerRequest &  req,
rc_hand_eye_calibration_client::TriggerResponse &  res 
)
private

store hand eye calibration on sensor

Definition at line 101 of file rc_hand_eye_calibration_client.cpp.

void rc_hand_eye_calibration_client::HandEyeCalibClient::sendCachedCalibration ( const ros::SteadyTimerEvent = ros::SteadyTimerEvent())
private

Definition at line 201 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::setCalibSrv ( rc_hand_eye_calibration_client::SetCalibrationRequest &  req,
rc_hand_eye_calibration_client::SetCalibrationResponse &  res 
)
private

Service call to set the calibration.

Definition at line 168 of file rc_hand_eye_calibration_client.cpp.

bool rc_hand_eye_calibration_client::HandEyeCalibClient::setSlotSrv ( rc_hand_eye_calibration_client::SetCalibrationPoseRequest &  req,
rc_hand_eye_calibration_client::SetCalibrationPoseResponse &  res 
)
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 130 of file rc_hand_eye_calibration_client.cpp.

void rc_hand_eye_calibration_client::HandEyeCalibClient::updateCalibrationCache ( const rc_hand_eye_calibration_client::CalibrationResponse &  res)
private

Copy resp into current_calibration_.

Definition at line 190 of file rc_hand_eye_calibration_client.cpp.

Member Data Documentation

std::string rc_hand_eye_calibration_client::HandEyeCalibClient::base_frame_id_ = "base_link"
private

Definition at line 137 of file rc_hand_eye_calibration_client.h.

double rc_hand_eye_calibration_client::HandEyeCalibClient::calib_publish_period_ = 0.0
private

Whether to send the transformation periodically instead of as a static transformation Zero or negative value: static tf (via latched topic, sends updates on new calibration response)

Definition at line 140 of file rc_hand_eye_calibration_client.h.

ros::SteadyTimer rc_hand_eye_calibration_client::HandEyeCalibClient::calib_publish_timer_
private

Definition at line 141 of file rc_hand_eye_calibration_client.h.

double rc_hand_eye_calibration_client::HandEyeCalibClient::calib_request_period_ = 0.0
private

If non-negative: Periodically update the calibration by requesting it.

If zero: Request only once

Definition at line 144 of file rc_hand_eye_calibration_client.h.

ros::SteadyTimer rc_hand_eye_calibration_client::HandEyeCalibClient::calib_request_timer_
private

Definition at line 145 of file rc_hand_eye_calibration_client.h.

std::string rc_hand_eye_calibration_client::HandEyeCalibClient::camera_frame_id_ = "camera"
private

Default Frame Ids to be used for the tf broadcast.

Definition at line 134 of file rc_hand_eye_calibration_client.h.

geometry_msgs::TransformStamped rc_hand_eye_calibration_client::HandEyeCalibClient::current_calibration_
private

Definition at line 132 of file rc_hand_eye_calibration_client.h.

tf2_ros::TransformBroadcaster rc_hand_eye_calibration_client::HandEyeCalibClient::dynamic_tf2_broadcaster_
private

To be used for periodic sending.

Definition at line 131 of file rc_hand_eye_calibration_client.h.

std::string rc_hand_eye_calibration_client::HandEyeCalibClient::endeff_frame_id_ = "end_effector"
private

Which one is used depends on the value of "robot_mounted" in the calibration response.

Definition at line 136 of file rc_hand_eye_calibration_client.h.

std::tuple<size_t, size_t, size_t> rc_hand_eye_calibration_client::HandEyeCalibClient::image_version_
private

Definition at line 151 of file rc_hand_eye_calibration_client.h.

ros::NodeHandle rc_hand_eye_calibration_client::HandEyeCalibClient::nh_
private

Definition at line 119 of file rc_hand_eye_calibration_client.h.

rc_rest_api::RestHelper rc_hand_eye_calibration_client::HandEyeCalibClient::rest_helper_
private

Definition at line 149 of file rc_hand_eye_calibration_client.h.

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

Definition at line 146 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_calibrate_
private

Definition at line 122 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_get_result_
private

Definition at line 126 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_publish_transform_
private

Definition at line 125 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_remove_
private

Definition at line 124 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_reset_
private

Definition at line 123 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_save_
private

Definition at line 121 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_set_calibration_
private

Definition at line 127 of file rc_hand_eye_calibration_client.h.

ros::ServiceServer rc_hand_eye_calibration_client::HandEyeCalibClient::srv_set_slot_
private

Definition at line 120 of file rc_hand_eye_calibration_client.h.

tf2_ros::StaticTransformBroadcaster rc_hand_eye_calibration_client::HandEyeCalibClient::static_tf2_broadcaster_
private

To be used for on-change sending only.

Definition at line 129 of file rc_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 Sat Feb 13 2021 03:41:55