service_stopper.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017, 2018 Simon Rasmussen (refactor)
3  *
4  * Copyright 2015, 2016 Thomas Timm Andersen (original version)
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
20 
21 ServiceStopper::ServiceStopper(std::vector<Service*> services)
22  : enable_service_(nh_.advertiseService("ur_driver/robot_enable", &ServiceStopper::enableCallback, this))
23  , services_(services)
24  , last_state_(RobotState::Error)
25  , activation_mode_(ActivationMode::Never)
26 {
27  std::string mode;
28  ros::param::param("~require_activation", mode, std::string("Never"));
29  if (mode == "Always")
30  {
32  }
33  else if (mode == "OnStartup")
34  {
36  }
37  else
38  {
39  if (mode != "Never")
40  {
41  LOG_WARN("Found invalid value for param require_activation: '%s'\nShould be one of Never, OnStartup, Always",
42  mode.c_str());
43  mode = "Never";
44  }
46  }
47 
48  LOG_INFO("Service 'ur_driver/robot_enable' activation mode: %s", mode.c_str());
49 }
50 
51 bool ServiceStopper::enableCallback(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& resp)
52 {
53  // After the startup call OnStartup and Never behave the same
57  return true;
58 }
59 
61 {
62  if (last_state_ == state)
63  return;
64 
65  for (auto const service : services_)
66  {
67  service->onRobotStateChange(state);
68  }
69 
70  last_state_ = state;
71 }
72 
74 {
75  if (data.emergency_stopped)
76  {
78  }
79  else if (data.protective_stopped)
80  {
82  }
83  else if (error)
84  {
86  }
88  {
89  // No error encountered, the user requested automatic reactivation
91  }
92 
93  return true;
94 }
Error
bool param(const std::string &param_name, T &param_val, const T &default_val)
ActivationMode activation_mode_
bool handle(SharedRobotModeData &data, bool error)
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
void notify_all(RobotState state)
RobotState last_state_
#define LOG_INFO(format,...)
Definition: log.h:35
bool enableCallback(std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &resp)
std::vector< Service * > services_
RobotState
ActivationMode
ServiceStopper(std::vector< Service * > services)
#define LOG_WARN(format,...)
Definition: log.h:34


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:00