1 #ifndef REST_HAND_EYE_CALIBRATION_CLIENT_H 2 #define REST_HAND_EYE_CALIBRATION_CLIENT_H 4 #include <rc_hand_eye_calibration_client/SetCalibrationPose.h> 5 #include <rc_hand_eye_calibration_client/Calibration.h> 6 #include <rc_hand_eye_calibration_client/hand_eye_calibrationConfig.h> 8 #include <std_srvs/Trigger.h> 11 #include <dynamic_reconfigure/server.h> 30 bool calibSrv(rc_hand_eye_calibration_client::CalibrationRequest &request,
31 rc_hand_eye_calibration_client::CalibrationResponse &
response);
34 bool getCalibResultSrv(rc_hand_eye_calibration_client::CalibrationRequest &request,
35 rc_hand_eye_calibration_client::CalibrationResponse &response);
38 bool saveSrv(std_srvs::TriggerRequest &request,
39 std_srvs::TriggerResponse &response);
42 bool resetSrv(std_srvs::TriggerRequest &request,
43 std_srvs::TriggerResponse &response);
46 bool removeSrv(std_srvs::TriggerRequest &request,
47 std_srvs::TriggerResponse &response);
51 bool setSlotSrv(rc_hand_eye_calibration_client::SetCalibrationPoseRequest &request,
52 rc_hand_eye_calibration_client::SetCalibrationPoseResponse &response);
59 void dynamicReconfigureCb(rc_hand_eye_calibration_client::hand_eye_calibrationConfig &config, uint32_t);
70 std::unique_ptr<dynamic_reconfigure::Server<rc_hand_eye_calibration_client::hand_eye_calibrationConfig> >
server_;
bool saveSrv(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
store hand eye calibration on sensor
ros::ServiceServer srv_save_
bool removeSrv(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Remove calibration so sensor reports as uncalibrated.
std::unique_ptr< dynamic_reconfigure::Server< rc_hand_eye_calibration_client::hand_eye_calibrationConfig > > server_
void dynamicReconfigureCb(rc_hand_eye_calibration_client::hand_eye_calibrationConfig &config, uint32_t)
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.
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.
bool resetSrv(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Delete all stored data, e.g., to start over.
void advertiseServices()
Advertises the services in the namespace of nh_.
bool calibSrv(rc_hand_eye_calibration_client::CalibrationRequest &request, rc_hand_eye_calibration_client::CalibrationResponse &response)
Perform the calibration and return its result.
ros::ServiceServer srv_publish_transform_
ros::ServiceServer srv_reset_
CalibrationWrapper(std::string host, ros::NodeHandle nh)
ros::ServiceServer srv_get_result_
ros::ServiceServer srv_set_slot_
ros::ServiceServer srv_remove_
const std::string response
ros::ServiceServer srv_calibrate_