46 #include <controller_manager_msgs/SwitchController.h>
47 #include <control_msgs/QueryCalibrationState.h>
48 #include <rm_msgs/StatusChange.h>
52 template <
class ServiceType>
53 class ServiceCallerBase
74 if (controllers.
hasMember(
"service_name"))
75 service_name_ =
static_cast<std::string
>(controllers[
"service_name"]);
79 if (service_name.empty())
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_);
114 ROS_INFO_ONCE(
"Failed to call service %s on %s. Retrying now ...",
typeid(ServiceType).name(),
147 service_.request.start_controllers = controllers;
151 service_.request.stop_controllers = controllers;
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;
205 void setEnemyColor(
const int& robot_id_,
const std::string& robot_color_)
210 robot_color_ ==
"blue" ? rm_msgs::StatusChangeRequest::RED : rm_msgs::StatusChangeRequest::BLUE;
224 service_.request.color =
service_.request.color == rm_msgs::StatusChangeRequest::RED;
228 service_.request.target =
service_.request.target == rm_msgs::StatusChangeRequest::ARMOR;
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 :
258 return service_.request.armor_target;
268 return service_.response.switch_is_success;