adapter_operation_mode.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 ADAPTER_OPERATION_MODE_H
19 #define ADAPTER_OPERATION_MODE_H
20 
21 #include <mutex>
22 
23 #include <ros/ros.h>
24 
25 #include <prbt_hardware_support/GetOperationMode.h>
26 #include <prbt_hardware_support/IsBrakeTestRequired.h>
27 #include <prbt_hardware_support/OperationModes.h>
28 
30 {
31 
36 {
37 public:
39  virtual ~AdapterOperationMode() = default;
40 
41 protected:
45  void updateOperationMode(const OperationModes& mode);
46 
47 private:
52 
53  bool getOperationMode(GetOperationMode::Request&,
54  GetOperationMode::Response& response);
55 
56 private:
58  OperationModes op_mode_;
59 
61  std::mutex op_mode_mutex_;
62 
65 
68 
71 };
72 
73 } // namespace prbt_hardware_support
74 #endif // ADAPTER_OPERATION_MODE_H
ros::NodeHandle & nh_
The node handle.
OperationModes op_mode_
Store the current operation mode according to OperationModes.msg.
bool getOperationMode(GetOperationMode::Request &, GetOperationMode::Response &response)
void updateOperationMode(const OperationModes &mode)
Stores the operation mode and publishes it, if it has changed.
ros::Publisher operation_mode_pub_
Informs about operation mode changes via topic.
void initOperationModeService()
Initializes the operation mode service.
std::mutex op_mode_mutex_
Protects read/write of the operation mode.
ros::ServiceServer operation_mode_server_
Server serving a service to ask whether a brake test is currently required.
Publishes information on the active operation mode. Also offers a service for querying the operation ...


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