rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
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
50namespace rm_common
51{
52template <class ServiceType>
54{
55public:
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 = "")
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 }
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 }
103 {
104 std::unique_lock<std::mutex> guard(mutex_, std::try_to_lock);
105 return !guard.owns_lock();
106 }
107
108protected:
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 {
118 fail_count_++;
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_;
129 ros::ServiceClient client_;
130 ServiceType service_;
131 std::thread* thread_{};
132 std::mutex mutex_;
133 int fail_count_, fail_limit_;
134};
135
136class SwitchControllersServiceCaller : public ServiceCallerBase<controller_manager_msgs::SwitchController>
137{
138public:
139 explicit SwitchControllersServiceCaller(ros::NodeHandle& nh)
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
161class QueryCalibrationServiceCaller : public ServiceCallerBase<control_msgs::QueryCalibrationState>
162{
163public:
164 explicit QueryCalibrationServiceCaller(ros::NodeHandle& nh)
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 }
172 QueryCalibrationServiceCaller(XmlRpc::XmlRpcValue& controllers, ros::NodeHandle& nh)
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
184class SwitchDetectionCaller : public ServiceCallerBase<rm_msgs::StatusChange>
185{
186public:
187 explicit SwitchDetectionCaller(ros::NodeHandle& nh)
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;
193 callService();
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 }
223 {
224 service_.request.color = service_.request.color == rm_msgs::StatusChangeRequest::RED;
225 }
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 }
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 }
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 }
249 {
250 return service_.request.color;
251 }
253 {
254 return service_.request.target;
255 }
257 {
258 return service_.request.armor_target;
259 }
261 {
262 return service_.request.exposure;
263 }
265 {
266 if (isCalling())
267 return false;
268 return service_.response.switch_is_success;
269 }
270
271private:
272 bool is_set_{};
273};
274
275} // namespace rm_common
Definition service_caller.h:162
QueryCalibrationServiceCaller(ros::NodeHandle &nh, std::string &service_name)
Definition service_caller.h:168
QueryCalibrationServiceCaller(XmlRpc::XmlRpcValue &controllers, ros::NodeHandle &nh)
Definition service_caller.h:172
bool isCalibrated()
Definition service_caller.h:176
QueryCalibrationServiceCaller(ros::NodeHandle &nh)
Definition service_caller.h:164
Definition service_caller.h:54
std::mutex mutex_
Definition service_caller.h:132
int fail_limit_
Definition service_caller.h:133
bool isCalling()
Definition service_caller.h:102
ros::ServiceClient client_
Definition service_caller.h:129
ServiceCallerBase(ros::NodeHandle &nh, std::string &service_name)
Definition service_caller.h:66
ServiceCallerBase(XmlRpc::XmlRpcValue &controllers, ros::NodeHandle &nh, const std::string &service_name="")
Definition service_caller.h:71
std::string service_name_
Definition service_caller.h:128
int fail_count_
Definition service_caller.h:133
ServiceType & getService()
Definition service_caller.h:98
ServiceCallerBase(ros::NodeHandle &nh, const std::string &service_name="")
Definition service_caller.h:56
~ServiceCallerBase()
Definition service_caller.h:87
ServiceType service_
Definition service_caller.h:130
void callService()
Definition service_caller.h:91
void callingThread()
Definition service_caller.h:109
Definition service_caller.h:137
void startControllers(const std::vector< std::string > &controllers)
Definition service_caller.h:145
void stopControllers(const std::vector< std::string > &controllers)
Definition service_caller.h:149
bool getOk()
Definition service_caller.h:153
SwitchControllersServiceCaller(ros::NodeHandle &nh)
Definition service_caller.h:139
Definition service_caller.h:185
int getArmorTarget()
Definition service_caller.h:256
void setColor(uint8_t color)
Definition service_caller.h:218
void switchTargetType()
Definition service_caller.h:226
SwitchDetectionCaller(ros::NodeHandle &nh, std::string service_name)
Definition service_caller.h:196
void setTargetType(uint8_t target)
Definition service_caller.h:230
void setArmorTargetType(uint8_t armor_target)
Definition service_caller.h:238
int getTarget()
Definition service_caller.h:252
void switchArmorTargetType()
Definition service_caller.h:234
int getColor()
Definition service_caller.h:248
void switchEnemyColor()
Definition service_caller.h:222
uint8_t getExposureLevel()
Definition service_caller.h:260
bool getIsSwitch()
Definition service_caller.h:264
SwitchDetectionCaller(ros::NodeHandle &nh)
Definition service_caller.h:187
void setEnemyColor(const int &robot_id_, const std::string &robot_color_)
Definition service_caller.h:205
void switchExposureLevel()
Definition service_caller.h:242
Definition calibration_queue.h:44