33 #ifndef RC_PICK_CLIENT_PICK_CLIENT_H 34 #define RC_PICK_CLIENT_PICK_CLIENT_H 36 #include <std_srvs/Trigger.h> 39 #include <dynamic_reconfigure/server.h> 42 #include <rc_pick_client/DetectLoadCarriers.h> 43 #include <rc_pick_client/DeleteLoadCarriers.h> 44 #include <rc_pick_client/DeleteRegionsOfInterest.h> 45 #include <rc_pick_client/GetLoadCarriers.h> 46 #include <rc_pick_client/DetectFillingLevel.h> 47 #include <rc_pick_client/GetRegionsOfInterest.h> 48 #include <rc_pick_client/SetLoadCarrier.h> 49 #include <rc_pick_client/SetRegionOfInterest.h> 50 #include <rc_pick_client/pickModuleConfig.h> 51 #include "json/json.hpp" 70 std::unique_ptr<dynamic_reconfigure::Server<rc_pick_client::pickModuleConfig>>
server_;
86 void paramsToCfg(
const json& params, rc_pick_client::pickModuleConfig& cfg);
88 template <
typename Request,
typename Response>
89 bool callService(
const std::string& name,
const Request& req, Response& res)
98 catch (
const std::exception& ex)
101 res.return_code.value = -2;
102 res.return_code.message = ex.what();
108 rc_pick_client::DetectLoadCarriersResponse& response);
111 rc_pick_client::DeleteLoadCarriersResponse& response);
114 rc_pick_client::GetLoadCarriersResponse& response);
116 bool setLoadCarrier(rc_pick_client::SetLoadCarrierRequest& request, rc_pick_client::SetLoadCarrierResponse& response);
119 rc_pick_client::DetectFillingLevelResponse& response);
121 bool deleteROISrv(rc_pick_client::DeleteRegionsOfInterestRequest& request,
122 rc_pick_client::DeleteRegionsOfInterestResponse& response);
124 bool getROIs(rc_pick_client::GetRegionsOfInterestRequest& request,
125 rc_pick_client::GetRegionsOfInterestResponse& response);
127 bool setROI(rc_pick_client::SetRegionOfInterestRequest& request,
128 rc_pick_client::SetRegionOfInterestResponse& response);
142 #endif // RC_PICK_CLIENT_PICK_CLIENT_H
PickClient(const std::string &host, const std::string &node_name, const ros::NodeHandle &nh)
bool detectLoadCarriersSrv(rc_pick_client::DetectLoadCarriersRequest &request, rc_pick_client::DetectLoadCarriersResponse &response)
ros::ServiceServer srv_detect_filling_level_
ros::ServiceServer srv_set_lc_
bool deleteROISrv(rc_pick_client::DeleteRegionsOfInterestRequest &request, rc_pick_client::DeleteRegionsOfInterestResponse &response)
bool setROI(rc_pick_client::SetRegionOfInterestRequest &request, rc_pick_client::SetRegionOfInterestResponse &response)
ros::ServiceServer srv_detect_lc_
ros::ServiceServer srv_get_lcs_
ros::ServiceServer srv_get_rois_
ros::ServiceServer srv_set_roi_
std::unique_ptr< dynamic_reconfigure::Server< rc_pick_client::pickModuleConfig > > server_
json createSharedParameters(rc_pick_client::pickModuleConfig &config)
ros::ServiceServer srv_delete_rois_
ros::ServiceServer srv_delete_lcs_
bool setLoadCarrier(rc_pick_client::SetLoadCarrierRequest &request, rc_pick_client::SetLoadCarrierResponse &response)
bool detectFillingLevelSrv(rc_pick_client::DetectFillingLevelRequest &request, rc_pick_client::DetectFillingLevelResponse &response)
bool getLoadCarriers(rc_pick_client::GetLoadCarriersRequest &request, rc_pick_client::GetLoadCarriersResponse &response)
bool getROIs(rc_pick_client::GetRegionsOfInterestRequest &request, rc_pick_client::GetRegionsOfInterestResponse &response)
bool callService(const std::string &name, const Request &req, Response &res)
void paramsToCfg(const json ¶ms, rc_pick_client::pickModuleConfig &cfg)
bool deleteLoadCarriersSrv(rc_pick_client::DeleteLoadCarriersRequest &request, rc_pick_client::DeleteLoadCarriersResponse &response)
pick_visualization::Visualization visualizer_
virtual void dynamicReconfigureCallback(rc_pick_client::pickModuleConfig &config, uint32_t)=0
rc_rest_api::RestHelper rest_helper_
json servicePutRequest(const std::string &service_name)