operation_mode_setup_executor.h
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 #ifndef OPERATION_MODE_SETUP_EXECUTOR_H
19 #define OPERATION_MODE_SETUP_EXECUTOR_H
20 
21 #include <atomic>
22 
23 #include <ros/ros.h>
24 
25 #include <pilz_msgs/GetSpeedOverride.h>
26 #include <pilz_msgs/OperationModes.h>
27 
30 
31 namespace prbt_hardware_support
32 {
38 {
39 public:
45  OperationModeSetupExecutor(const MonitorCartesianSpeedFunc& monitor_cartesian_speed_func);
46 
47 public:
51  void updateOperationMode(const pilz_msgs::OperationModes& operation_mode);
52 
53  bool getSpeedOverride(pilz_msgs::GetSpeedOverride::Request& /*req*/, pilz_msgs::GetSpeedOverride::Response& response);
54 
55 private:
57  std::atomic<double> speed_override_{ 0.0 };
58 
63 };
64 
65 } // namespace prbt_hardware_support
66 
67 #endif // OPERATION_MODE_SETUP_EXECUTOR_H
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.
Activates speed monitoring and sets the speed override based on the current operation mode...
std::function< bool(const bool)> MonitorCartesianSpeedFunc
OperationModeSetupExecutor(const MonitorCartesianSpeedFunc &monitor_cartesian_speed_func)
Ctor.
const std::string response


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