TODO.
More...
#include <rest_hand_eye_calibration_client.h>
|
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...
|
|
CalibrationWrapper::CalibrationWrapper |
( |
std::string |
host, |
|
|
ros::NodeHandle |
nh |
|
) |
| |
void CalibrationWrapper::advertiseServices |
( |
| ) |
|
|
private |
bool CalibrationWrapper::calibSrv |
( |
rc_hand_eye_calibration_client::CalibrationRequest & |
request, |
|
|
rc_hand_eye_calibration_client::CalibrationResponse & |
response |
|
) |
| |
|
private |
void CalibrationWrapper::dynamicReconfigureCb |
( |
rc_hand_eye_calibration_client::hand_eye_calibrationConfig & |
config, |
|
|
uint32_t |
|
|
) |
| |
|
private |
bool CalibrationWrapper::getCalibResultSrv |
( |
rc_hand_eye_calibration_client::CalibrationRequest & |
request, |
|
|
rc_hand_eye_calibration_client::CalibrationResponse & |
response |
|
) |
| |
|
private |
void CalibrationWrapper::initConfiguration |
( |
| ) |
|
|
private |
bool CalibrationWrapper::removeSrv |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
private |
bool CalibrationWrapper::resetSrv |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
private |
bool CalibrationWrapper::saveSrv |
( |
std_srvs::TriggerRequest & |
request, |
|
|
std_srvs::TriggerResponse & |
response |
|
) |
| |
|
private |
bool CalibrationWrapper::setSlotSrv |
( |
rc_hand_eye_calibration_client::SetCalibrationPoseRequest & |
request, |
|
|
rc_hand_eye_calibration_client::SetCalibrationPoseResponse & |
response |
|
) |
| |
|
private |
std::string CalibrationWrapper::host_ |
|
private |
std::string CalibrationWrapper::paramsUrl_ |
|
private |
std::unique_ptr<dynamic_reconfigure::Server<rc_hand_eye_calibration_client::hand_eye_calibrationConfig> > CalibrationWrapper::server_ |
|
private |
std::string CalibrationWrapper::servicesUrl_ |
|
private |
int CalibrationWrapper::timeoutCurl_ |
|
private |
The documentation for this class was generated from the following files: