18 #ifndef ADAPTER_OPERATION_MODE_H 19 #define ADAPTER_OPERATION_MODE_H 25 #include <pilz_msgs/GetOperationMode.h> 26 #include <pilz_msgs/OperationModes.h> 51 bool getOperationMode(pilz_msgs::GetOperationMode::Request& req, pilz_msgs::GetOperationMode::Response& res);
71 #endif // ADAPTER_OPERATION_MODE_H ros::NodeHandle & nh_
The node handle.
void updateOperationMode(const pilz_msgs::OperationModes &mode)
Stores the operation mode and publishes it, if it has changed.
virtual ~AdapterOperationMode()=default
ros::Publisher operation_mode_pub_
Informs about operation mode changes via topic.
pilz_msgs::OperationModes op_mode_
Store the current operation mode according to OperationModes.msg.
void initOperationModeService()
Initializes the operation mode service.
AdapterOperationMode(ros::NodeHandle &nh)
bool getOperationMode(pilz_msgs::GetOperationMode::Request &req, pilz_msgs::GetOperationMode::Response &res)
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 ...