45#include <ros/service.h>
46#include <controller_manager_msgs/SwitchController.h>
47#include <control_msgs/QueryCalibrationState.h>
48#include <rm_msgs/StatusChange.h>
52template <
class ServiceType>
59 if (!nh.param(
"service_name",
service_name_, service_name) && service_name.empty())
61 ROS_ERROR(
"Service name no defined (namespace: %s)", nh.getNamespace().c_str());
71 ServiceCallerBase(XmlRpc::XmlRpcValue& controllers, ros::NodeHandle& nh,
const std::string& service_name =
"")
74 if (controllers.hasMember(
"service_name"))
75 service_name_ =
static_cast<std::string
>(controllers[
"service_name"]);
78 service_name_ = service_name;
79 if (service_name.empty())
81 ROS_ERROR(
"Service name no defined (namespace: %s)", nh.getNamespace().c_str());
71 ServiceCallerBase(XmlRpc::XmlRpcValue& controllers, ros::NodeHandle& nh,
const std::string& service_name =
"") {
…}
104 std::unique_lock<std::mutex> guard(mutex_, std::try_to_lock);
105 return !guard.owns_lock();
111 std::lock_guard<std::mutex> guard(mutex_);
112 if (!client_.call(service_))
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)
119 if (fail_count_ >= fail_limit_)
121 ROS_ERROR_ONCE(
"Failed to call service %s on %s",
typeid(ServiceType).name(), service_name_.c_str());
131 std::thread* thread_{};
140 :
ServiceCallerBase<controller_manager_msgs::SwitchController>(nh,
"/controller_manager/switch_controller")
142 service_.request.strictness = service_.request.BEST_EFFORT;
143 service_.request.start_asap =
true;
147 service_.request.start_controllers = controllers;
151 service_.request.stop_controllers = controllers;
157 return service_.response.ok;
180 return service_.response.is_calibrated;
188 :
ServiceCallerBase<rm_msgs::StatusChange>(nh,
"/detection_nodelet/status_switch")
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;
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;
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"));
216 ROS_INFO_STREAM(
"Set enemy color failed: referee offline");
220 service_.request.color = color;
224 service_.request.color = service_.request.color == rm_msgs::StatusChangeRequest::RED;
228 service_.request.target = service_.request.target == rm_msgs::StatusChangeRequest::ARMOR;
232 service_.request.target = target;
236 service_.request.armor_target = service_.request.armor_target == rm_msgs::StatusChangeRequest::ARMOR_ALL;
240 service_.request.armor_target = armor_target;
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;
250 return service_.request.color;
254 return service_.request.target;
258 return service_.request.armor_target;
262 return service_.request.exposure;
268 return service_.response.switch_is_success;
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