18 #include <boost/optional.hpp> 25 : monitor_cartesian_speed_func_(monitor_cartesian_speed_func)
31 ROS_DEBUG(
"updateOperationMode: %d", operation_mode.value);
38 boost::optional<bool> monitor_cartesian_speed{ boost::none };
39 switch (operation_mode.value)
41 case pilz_msgs::OperationModes::T1:
42 monitor_cartesian_speed =
true;
45 case pilz_msgs::OperationModes::AUTO:
46 monitor_cartesian_speed =
false;
61 pilz_msgs::GetSpeedOverride::Response& response)
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.