operation_mode_setup_executor.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <boost/optional.hpp>
19 
21 
22 namespace prbt_hardware_support
23 {
25  : monitor_cartesian_speed_func_(monitor_cartesian_speed_func)
26 {
27 }
28 
29 void OperationModeSetupExecutor::updateOperationMode(const pilz_msgs::OperationModes& operation_mode)
30 {
31  ROS_DEBUG("updateOperationMode: %d", operation_mode.value);
32  if (operation_mode.time_stamp <= time_stamp_last_op_mode_)
33  {
34  return;
35  }
36  time_stamp_last_op_mode_ = operation_mode.time_stamp;
37 
38  boost::optional<bool> monitor_cartesian_speed{ boost::none };
39  switch (operation_mode.value)
40  {
41  case pilz_msgs::OperationModes::T1:
42  monitor_cartesian_speed = true;
43  speed_override_ = 0.1;
44  break;
45  case pilz_msgs::OperationModes::AUTO:
46  monitor_cartesian_speed = false;
47  speed_override_ = 1.0;
48  break;
49  default:
50  speed_override_ = 0.0;
51  break;
52  }
53 
54  if (monitor_cartesian_speed && monitor_cartesian_speed_func_)
55  {
56  monitor_cartesian_speed_func_(monitor_cartesian_speed.get());
57  }
58 }
59 
60 bool OperationModeSetupExecutor::getSpeedOverride(pilz_msgs::GetSpeedOverride::Request& /*req*/,
61  pilz_msgs::GetSpeedOverride::Response& response)
62 {
63  response.speed_override = speed_override_;
64  return true;
65 }
66 
67 } // namespace prbt_hardware_support
bool getSpeedOverride(pilz_msgs::GetSpeedOverride::Request &, pilz_msgs::GetSpeedOverride::Response &response)
std::atomic< double > speed_override_
The active speed override.
void updateOperationMode(const pilz_msgs::OperationModes &operation_mode)
Function to be called whenever a new operation mode is set.
MonitorCartesianSpeedFunc monitor_cartesian_speed_func_
Function used to (de-)activate cartesian speed monitoring.
ros::Time time_stamp_last_op_mode_
Time stamp of the last received operation mode.
std::function< bool(const bool)> MonitorCartesianSpeedFunc
OperationModeSetupExecutor(const MonitorCartesianSpeedFunc &monitor_cartesian_speed_func)
Ctor.
#define ROS_DEBUG(...)


prbt_hardware_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:34