rest_hand_eye_calibration_client.h
Go to the documentation of this file.
1 #ifndef REST_HAND_EYE_CALIBRATION_CLIENT_H
2 #define REST_HAND_EYE_CALIBRATION_CLIENT_H
3 
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>
7 
8 #include <std_srvs/Trigger.h>
9 
10 #include <ros/ros.h>
11 #include <dynamic_reconfigure/server.h>
12 
13 #include <memory>
14 
15 
20 {
21  public:
22 
23  CalibrationWrapper(std::string host, ros::NodeHandle nh);
24 
25  private:
26 
30  bool calibSrv(rc_hand_eye_calibration_client::CalibrationRequest &request,
31  rc_hand_eye_calibration_client::CalibrationResponse &response);
32 
34  bool getCalibResultSrv(rc_hand_eye_calibration_client::CalibrationRequest &request,
35  rc_hand_eye_calibration_client::CalibrationResponse &response);
36 
38  bool saveSrv(std_srvs::TriggerRequest &request,
39  std_srvs::TriggerResponse &response);
40 
42  bool resetSrv(std_srvs::TriggerRequest &request,
43  std_srvs::TriggerResponse &response);
44 
46  bool removeSrv(std_srvs::TriggerRequest &request,
47  std_srvs::TriggerResponse &response);
48 
51  bool setSlotSrv(rc_hand_eye_calibration_client::SetCalibrationPoseRequest &request,
52  rc_hand_eye_calibration_client::SetCalibrationPoseResponse &response);
53 
55  void advertiseServices();
56 
57  void initConfiguration();
58 
59  void dynamicReconfigureCb(rc_hand_eye_calibration_client::hand_eye_calibrationConfig &config, uint32_t);
60 
61  //ROS Stuff
70  std::unique_ptr<dynamic_reconfigure::Server<rc_hand_eye_calibration_client::hand_eye_calibrationConfig> > server_;
71 
72  // REST stuff
73  std::string host_, servicesUrl_, paramsUrl_;
74  int timeoutCurl_; // ms
75 
76 };
77 #endif
bool saveSrv(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
store hand eye calibration on sensor
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_
CalibrationWrapper(std::string host, ros::NodeHandle nh)
const std::string response


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