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 
19 
20 namespace prbt_hardware_support
21 {
22 
23 
25  const double& speed_limit_auto,
26  const SetSpeedLimitFunc& set_speed_limit_func)
27  : speed_limit_t1_(speed_limit_t1)
28  , speed_limit_auto_(speed_limit_auto)
29  , set_speed_limit_func_(set_speed_limit_func)
30 {
31 }
32 
33 
34 void OperationModeSetupExecutor::updateOperationMode(const OperationModes& operation_mode)
35 {
36  ROS_DEBUG("updateOperationMode: %d", operation_mode.value);
37  if (operation_mode.time_stamp <= time_stamp_last_op_mode_)
38  {
39  return;
40  }
41  time_stamp_last_op_mode_ = operation_mode.time_stamp;
42 
43  double speed_limit {0};
44  switch(operation_mode.value)
45  {
46  case OperationModes::T1:
47  speed_limit = speed_limit_t1_;
48  speed_override_ = 0.1;
49  break;
50  case OperationModes::AUTO:
51  speed_limit = speed_limit_auto_;
52  speed_override_ = 1.0;
53  break;
54  default:
55  speed_override_ = 0.0;
56  break;
57  }
58 
60  {
61  set_speed_limit_func_(speed_limit);
62  }
63 }
64 
65 bool OperationModeSetupExecutor::getSpeedOverride(GetSpeedOverride::Request& /*req*/,
66  GetSpeedOverride::Response& response)
67 {
68  response.speed_override = speed_override_;
69  return true;
70 }
71 
72 
73 } // namespace prbt_hardware_support
std::atomic< double > speed_override_
The active speed override.
bool getSpeedOverride(GetSpeedOverride::Request &, GetSpeedOverride::Response &response)
ros::Time time_stamp_last_op_mode_
Time stamp of the last received operation mode.
SetSpeedLimitFunc set_speed_limit_func_
Function used to propagate speed limit changes into the system.
const double speed_limit_t1_
The allowed speed limit in operation mode T1.
const double speed_limit_auto_
The allowed speed limit in operation mode AUTOMATIC.
OperationModeSetupExecutor(const double &speed_limit_t1, const double &speed_limit_auto, const SetSpeedLimitFunc &set_speed_limit_func)
Ctor.
std::function< bool(const double &)> SetSpeedLimitFunc
void updateOperationMode(const OperationModes &operation_mode)
Function to be called whenever a new operation mode is set.
#define ROS_DEBUG(...)


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:17