pick_client.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Roboception GmbH
3  *
4  * Author: Monika Florek-Jasinska, Carlos Xavier Garcia Briones
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its contributors
17  * may be used to endorse or promote products derived from this software without
18  * specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
24  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef RC_PICK_CLIENT_PICK_CLIENT_H
34 #define RC_PICK_CLIENT_PICK_CLIENT_H
35 
36 #include <std_srvs/Trigger.h>
37 
38 #include <ros/ros.h>
39 #include <dynamic_reconfigure/server.h>
40 
41 #include <memory>
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"
52 #include "json_conversions.h"
53 
54 #include "rest_helper.h"
55 #include "visualization.h"
56 
58 
59 namespace ros_pick_client
60 {
62 {
63 public:
64  PickClient(const std::string& host, const std::string& node_name, const ros::NodeHandle& nh);
65 
66  virtual ~PickClient();
67 
68 protected:
70  std::unique_ptr<dynamic_reconfigure::Server<rc_pick_client::pickModuleConfig>> server_;
71 
73 
75 
84 
85  json createSharedParameters(rc_pick_client::pickModuleConfig& config);
86  void paramsToCfg(const json& params, rc_pick_client::pickModuleConfig& cfg);
87 
88  template <typename Request, typename Response>
89  bool callService(const std::string& name, const Request& req, Response& res)
90  {
91  try
92  {
93  json j_req = req;
94  const auto j_res = rest_helper_.servicePutRequest(name, j_req);
95  res = j_res;
96  return true;
97  }
98  catch (const std::exception& ex)
99  {
100  ROS_ERROR("%s", ex.what());
101  res.return_code.value = -2; // INTERNAL_ERROR
102  res.return_code.message = ex.what();
103  return false;
104  }
105  }
106 
107  bool detectLoadCarriersSrv(rc_pick_client::DetectLoadCarriersRequest& request,
108  rc_pick_client::DetectLoadCarriersResponse& response);
109 
110  bool deleteLoadCarriersSrv(rc_pick_client::DeleteLoadCarriersRequest& request,
111  rc_pick_client::DeleteLoadCarriersResponse& response);
112 
113  bool getLoadCarriers(rc_pick_client::GetLoadCarriersRequest& request,
114  rc_pick_client::GetLoadCarriersResponse& response);
115 
116  bool setLoadCarrier(rc_pick_client::SetLoadCarrierRequest& request, rc_pick_client::SetLoadCarrierResponse& response);
117 
118  bool detectFillingLevelSrv(rc_pick_client::DetectFillingLevelRequest& request,
119  rc_pick_client::DetectFillingLevelResponse& response);
120 
121  bool deleteROISrv(rc_pick_client::DeleteRegionsOfInterestRequest& request,
122  rc_pick_client::DeleteRegionsOfInterestResponse& response);
123 
124  bool getROIs(rc_pick_client::GetRegionsOfInterestRequest& request,
125  rc_pick_client::GetRegionsOfInterestResponse& response);
126 
127  bool setROI(rc_pick_client::SetRegionOfInterestRequest& request,
128  rc_pick_client::SetRegionOfInterestResponse& response);
129 
130  void startPick();
131 
132  void stopPick();
133 
134  void advertiseServices();
135 
136  void initConfiguration();
137 
138  virtual void dynamicReconfigureCallback(rc_pick_client::pickModuleConfig& config, uint32_t) = 0;
139 };
140 } // namespace ros_pick_client
141 
142 #endif // RC_PICK_CLIENT_PICK_CLIENT_H
nlohmann::json json
Definition: pick_client.h:57
PickClient(const std::string &host, const std::string &node_name, const ros::NodeHandle &nh)
Definition: pick_client.cpp:39
bool detectLoadCarriersSrv(rc_pick_client::DetectLoadCarriersRequest &request, rc_pick_client::DetectLoadCarriersResponse &response)
Definition: pick_client.cpp:94
ros::ServiceServer srv_detect_filling_level_
Definition: pick_client.h:77
ros::ServiceServer srv_set_lc_
Definition: pick_client.h:78
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_
Definition: pick_client.h:76
ros::ServiceServer srv_get_lcs_
Definition: pick_client.h:79
ros::ServiceServer srv_get_rois_
Definition: pick_client.h:82
ros::ServiceServer srv_set_roi_
Definition: pick_client.h:81
std::unique_ptr< dynamic_reconfigure::Server< rc_pick_client::pickModuleConfig > > server_
Definition: pick_client.h:70
json createSharedParameters(rc_pick_client::pickModuleConfig &config)
ros::ServiceServer srv_delete_rois_
Definition: pick_client.h:83
ros::ServiceServer srv_delete_lcs_
Definition: pick_client.h:80
bool setLoadCarrier(rc_pick_client::SetLoadCarrierRequest &request, rc_pick_client::SetLoadCarrierResponse &response)
Definition: pick_client.cpp:73
bool detectFillingLevelSrv(rc_pick_client::DetectFillingLevelRequest &request, rc_pick_client::DetectFillingLevelResponse &response)
bool getLoadCarriers(rc_pick_client::GetLoadCarriersRequest &request, rc_pick_client::GetLoadCarriersResponse &response)
Definition: pick_client.cpp:80
bool getROIs(rc_pick_client::GetRegionsOfInterestRequest &request, rc_pick_client::GetRegionsOfInterestResponse &response)
bool callService(const std::string &name, const Request &req, Response &res)
Definition: pick_client.h:89
void paramsToCfg(const json &params, rc_pick_client::pickModuleConfig &cfg)
bool deleteLoadCarriersSrv(rc_pick_client::DeleteLoadCarriersRequest &request, rc_pick_client::DeleteLoadCarriersResponse &response)
Definition: pick_client.cpp:87
pick_visualization::Visualization visualizer_
Definition: pick_client.h:74
virtual void dynamicReconfigureCallback(rc_pick_client::pickModuleConfig &config, uint32_t)=0
#define ROS_ERROR(...)
rc_rest_api::RestHelper rest_helper_
Definition: pick_client.h:72
json servicePutRequest(const std::string &service_name)
Definition: rest_helper.cpp:92


rc_pick_client
Author(s): Monika Florek-Jasinska
autogenerated on Sat Feb 13 2021 03:41:57