service_caller.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by qiayuan on 5/22/21.
36 //
37 
38 #pragma once
39 
40 #include <chrono>
41 #include <mutex>
42 #include <thread>
43 #include <utility>
44 #include <ros/ros.h>
45 #include <ros/service.h>
46 #include <controller_manager_msgs/SwitchController.h>
47 #include <control_msgs/QueryCalibrationState.h>
48 #include <rm_msgs/StatusChange.h>
49 
50 namespace rm_common
51 {
52 template <class ServiceType>
53 class ServiceCallerBase
54 {
55 public:
56  explicit ServiceCallerBase(ros::NodeHandle& nh, const std::string& service_name = "") : fail_count_(0), fail_limit_(0)
57  {
58  nh.param("fail_limit", fail_limit_, 0);
59  if (!nh.param("service_name", service_name_, service_name) && service_name.empty())
60  {
61  ROS_ERROR("Service name no defined (namespace: %s)", nh.getNamespace().c_str());
62  return;
63  }
64  client_ = nh.serviceClient<ServiceType>(service_name_);
65  }
66  ServiceCallerBase(ros::NodeHandle& nh, std::string& service_name) : fail_count_(0), fail_limit_(0)
67  {
68  service_name_ = service_name;
69  client_ = nh.serviceClient<ServiceType>(service_name_);
70  }
71  ServiceCallerBase(XmlRpc::XmlRpcValue& controllers, ros::NodeHandle& nh, const std::string& service_name = "")
72  : fail_count_(0), fail_limit_(0)
73  {
74  if (controllers.hasMember("service_name"))
75  service_name_ = static_cast<std::string>(controllers["service_name"]);
76  else
77  {
78  service_name_ = service_name;
79  if (service_name.empty())
80  {
81  ROS_ERROR("Service name no defined (namespace: %s)", nh.getNamespace().c_str());
82  return;
83  }
84  }
85  client_ = nh.serviceClient<ServiceType>(service_name_);
86  }
88  {
89  delete thread_;
90  }
91  void callService()
92  {
93  if (isCalling())
94  return;
95  thread_ = new std::thread(&ServiceCallerBase::callingThread, this);
96  thread_->detach();
97  }
98  ServiceType& getService()
99  {
100  return service_;
101  }
102  bool isCalling()
103  {
104  std::unique_lock<std::mutex> guard(mutex_, std::try_to_lock);
105  return !guard.owns_lock();
106  }
107 
108 protected:
109  void callingThread()
110  {
111  std::lock_guard<std::mutex> guard(mutex_);
112  if (!client_.call(service_))
113  {
114  ROS_INFO_ONCE("Failed to call service %s on %s. Retrying now ...", typeid(ServiceType).name(),
115  service_name_.c_str());
116  if (fail_limit_ != 0)
117  {
119  if (fail_count_ >= fail_limit_)
120  {
121  ROS_ERROR_ONCE("Failed to call service %s on %s", typeid(ServiceType).name(), service_name_.c_str());
122  fail_count_ = 0;
123  }
124  }
125  // ros::WallDuration(0.2).sleep();
126  }
127  }
128  std::string service_name_;
130  ServiceType service_;
131  std::thread* thread_{};
132  std::mutex mutex_;
134 };
135 
136 class SwitchControllersServiceCaller : public ServiceCallerBase<controller_manager_msgs::SwitchController>
137 {
138 public:
140  : ServiceCallerBase<controller_manager_msgs::SwitchController>(nh, "/controller_manager/switch_controller")
141  {
142  service_.request.strictness = service_.request.BEST_EFFORT;
143  service_.request.start_asap = true;
144  }
145  void startControllers(const std::vector<std::string>& controllers)
146  {
147  service_.request.start_controllers = controllers;
148  }
149  void stopControllers(const std::vector<std::string>& controllers)
150  {
151  service_.request.stop_controllers = controllers;
152  }
153  bool getOk()
154  {
155  if (isCalling())
156  return false;
157  return service_.response.ok;
158  }
159 };
160 
161 class QueryCalibrationServiceCaller : public ServiceCallerBase<control_msgs::QueryCalibrationState>
162 {
163 public:
165  : ServiceCallerBase<control_msgs::QueryCalibrationState>(nh)
166  {
167  }
168  QueryCalibrationServiceCaller(ros::NodeHandle& nh, std::string& service_name)
169  : ServiceCallerBase<control_msgs::QueryCalibrationState>(nh, service_name)
170  {
171  }
173  : ServiceCallerBase<control_msgs::QueryCalibrationState>(controllers, nh)
174  {
175  }
177  {
178  if (isCalling())
179  return false;
180  return service_.response.is_calibrated;
181  }
182 };
183 
184 class SwitchDetectionCaller : public ServiceCallerBase<rm_msgs::StatusChange>
185 {
186 public:
188  : ServiceCallerBase<rm_msgs::StatusChange>(nh, "/detection_nodelet/status_switch")
189  {
190  service_.request.target = rm_msgs::StatusChangeRequest::ARMOR;
191  service_.request.exposure = rm_msgs::StatusChangeRequest::EXPOSURE_LEVEL_0;
192  service_.request.armor_target = rm_msgs::StatusChangeRequest::ARMOR_ALL;
194  }
195 
196  explicit SwitchDetectionCaller(ros::NodeHandle& nh, std::string service_name)
197  : ServiceCallerBase<rm_msgs::StatusChange>(nh, service_name)
198  {
199  service_.request.target = rm_msgs::StatusChangeRequest::ARMOR;
200  service_.request.exposure = rm_msgs::StatusChangeRequest::EXPOSURE_LEVEL_0;
201  service_.request.armor_target = rm_msgs::StatusChangeRequest::ARMOR_ALL;
202  callService();
203  }
204 
205  void setEnemyColor(const int& robot_id_, const std::string& robot_color_)
206  {
207  if (robot_id_ != 0)
208  {
209  service_.request.color =
210  robot_color_ == "blue" ? rm_msgs::StatusChangeRequest::RED : rm_msgs::StatusChangeRequest::BLUE;
211  ROS_INFO_STREAM("Set enemy color: " << (service_.request.color == service_.request.RED ? "red" : "blue"));
212 
213  callService();
214  }
215  else
216  ROS_INFO_STREAM("Set enemy color failed: referee offline");
217  }
218  void setColor(uint8_t color)
219  {
220  service_.request.color = color;
221  }
222  void switchEnemyColor()
223  {
224  service_.request.color = service_.request.color == rm_msgs::StatusChangeRequest::RED;
225  }
226  void switchTargetType()
227  {
228  service_.request.target = service_.request.target == rm_msgs::StatusChangeRequest::ARMOR;
229  }
230  void setTargetType(uint8_t target)
231  {
232  service_.request.target = target;
233  }
234  void switchArmorTargetType()
235  {
236  service_.request.armor_target = service_.request.armor_target == rm_msgs::StatusChangeRequest::ARMOR_ALL;
237  }
238  void setArmorTargetType(uint8_t armor_target)
239  {
240  service_.request.armor_target = armor_target;
241  }
242  void switchExposureLevel()
243  {
244  service_.request.exposure = service_.request.exposure == rm_msgs::StatusChangeRequest::EXPOSURE_LEVEL_4 ?
245  rm_msgs::StatusChangeRequest::EXPOSURE_LEVEL_0 :
246  service_.request.exposure + 1;
247  }
248  int getColor()
249  {
250  return service_.request.color;
251  }
252  int getTarget()
253  {
254  return service_.request.target;
255  }
256  int getArmorTarget()
257  {
258  return service_.request.armor_target;
259  }
260  uint8_t getExposureLevel()
261  {
262  return service_.request.exposure;
263  }
264  bool getIsSwitch()
265  {
266  if (isCalling())
267  return false;
268  return service_.response.switch_is_success;
269  }
270 
271 private:
272  bool is_set_{};
273 };
274 
275 } // namespace rm_common
rm_common::SwitchControllersServiceCaller::stopControllers
void stopControllers(const std::vector< std::string > &controllers)
Definition: service_caller.h:180
rm_common::QueryCalibrationServiceCaller::QueryCalibrationServiceCaller
QueryCalibrationServiceCaller(ros::NodeHandle &nh)
Definition: service_caller.h:195
rm_common::SwitchDetectionCaller::switchExposureLevel
void switchExposureLevel()
Definition: service_caller.h:273
ROS_ERROR_ONCE
#define ROS_ERROR_ONCE(...)
rm_common::SwitchDetectionCaller::getArmorTarget
int getArmorTarget()
Definition: service_caller.h:287
ros.h
rm_common::SwitchDetectionCaller::switchTargetType
void switchTargetType()
Definition: service_caller.h:257
rm_common::SwitchDetectionCaller::getIsSwitch
bool getIsSwitch()
Definition: service_caller.h:295
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
service.h
rm_common::SwitchDetectionCaller::setTargetType
void setTargetType(uint8_t target)
Definition: service_caller.h:261
rm_common::QueryCalibrationServiceCaller
Definition: service_caller.h:192
rm_common::ServiceCallerBase::callingThread
void callingThread()
Definition: service_caller.h:171
rm_common::ServiceCallerBase::fail_count_
int fail_count_
Definition: service_caller.h:195
rm_common::ServiceCallerBase::fail_limit_
int fail_limit_
Definition: service_caller.h:195
rm_common::ServiceCallerBase::ServiceCallerBase
ServiceCallerBase(ros::NodeHandle &nh, const std::string &service_name="")
Definition: service_caller.h:118
rm_common::SwitchDetectionCaller::getTarget
int getTarget()
Definition: service_caller.h:283
rm_common::ServiceCallerBase
Definition: service_caller.h:84
rm_common::SwitchDetectionCaller::switchEnemyColor
void switchEnemyColor()
Definition: service_caller.h:253
rm_common::SwitchControllersServiceCaller::getOk
bool getOk()
Definition: service_caller.h:184
rm_common::ServiceCallerBase::getService
ServiceType & getService()
Definition: service_caller.h:160
rm_common::ServiceCallerBase::isCalling
bool isCalling()
Definition: service_caller.h:164
rm_common::ServiceCallerBase::client_
ros::ServiceClient client_
Definition: service_caller.h:191
rm_common::SwitchDetectionCaller::is_set_
bool is_set_
Definition: service_caller.h:303
ROS_INFO_ONCE
#define ROS_INFO_ONCE(...)
rm_common::ServiceCallerBase::mutex_
std::mutex mutex_
Definition: service_caller.h:194
rm_common
Definition: calibration_queue.h:43
rm_common::SwitchControllersServiceCaller::SwitchControllersServiceCaller
SwitchControllersServiceCaller(ros::NodeHandle &nh)
Definition: service_caller.h:170
ros::ServiceClient
rm_common::SwitchDetectionCaller::setColor
void setColor(uint8_t color)
Definition: service_caller.h:249
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rm_common::ServiceCallerBase::thread_
std::thread * thread_
Definition: service_caller.h:193
rm_common::SwitchControllersServiceCaller::startControllers
void startControllers(const std::vector< std::string > &controllers)
Definition: service_caller.h:176
rm_common::QueryCalibrationServiceCaller::isCalibrated
bool isCalibrated()
Definition: service_caller.h:207
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
rm_common::ServiceCallerBase::~ServiceCallerBase
~ServiceCallerBase()
Definition: service_caller.h:149
rm_common::SwitchDetectionCaller::switchArmorTargetType
void switchArmorTargetType()
Definition: service_caller.h:265
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
rm_common::SwitchDetectionCaller::getColor
int getColor()
Definition: service_caller.h:279
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rm_common::SwitchDetectionCaller::setEnemyColor
void setEnemyColor(const int &robot_id_, const std::string &robot_color_)
Definition: service_caller.h:236
rm_common::SwitchDetectionCaller::SwitchDetectionCaller
SwitchDetectionCaller(ros::NodeHandle &nh)
Definition: service_caller.h:218
rm_common::SwitchControllersServiceCaller
Definition: service_caller.h:167
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
rm_common::SwitchDetectionCaller::setArmorTargetType
void setArmorTargetType(uint8_t armor_target)
Definition: service_caller.h:269
rm_common::SwitchDetectionCaller::getExposureLevel
uint8_t getExposureLevel()
Definition: service_caller.h:291
rm_common::ServiceCallerBase::service_
ServiceType service_
Definition: service_caller.h:192
rm_common::ServiceCallerBase::service_name_
std::string service_name_
Definition: service_caller.h:190
rm_common::ServiceCallerBase::callService
void callService()
Definition: service_caller.h:153
XmlRpc::XmlRpcValue
ros::NodeHandle
rm_common::SwitchDetectionCaller
Definition: service_caller.h:215


rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01