Public Member Functions | Private Attributes | List of all members
prbt_hardware_support::OperationModeSetupExecutor Class Reference

Sets the allowed speed limit for each frame based on the current operation mode. More...

#include <operation_mode_setup_executor.h>

Public Member Functions

bool getSpeedOverride (GetSpeedOverride::Request &, GetSpeedOverride::Response &response)
 
 OperationModeSetupExecutor (const double &speed_limit_t1, const double &speed_limit_auto, const SetSpeedLimitFunc &set_speed_limit_func)
 Ctor. More...
 
void updateOperationMode (const OperationModes &operation_mode)
 Function to be called whenever a new operation mode is set. More...
 

Private Attributes

SetSpeedLimitFunc set_speed_limit_func_
 Function used to propagate speed limit changes into the system. More...
 
const double speed_limit_auto_
 The allowed speed limit in operation mode AUTOMATIC. More...
 
const double speed_limit_t1_
 The allowed speed limit in operation mode T1. More...
 
std::atomic< double > speed_override_ {0.0}
 The active speed override. More...
 
ros::Time time_stamp_last_op_mode_ {ros::Time(0)}
 Time stamp of the last received operation mode. More...
 

Detailed Description

Sets the allowed speed limit for each frame based on the current operation mode.

Definition at line 38 of file operation_mode_setup_executor.h.

Constructor & Destructor Documentation

prbt_hardware_support::OperationModeSetupExecutor::OperationModeSetupExecutor ( const double &  speed_limit_t1,
const double &  speed_limit_auto,
const SetSpeedLimitFunc set_speed_limit_func 
)

Ctor.

Parameters
speed_limit_t1limit Max allowed speed for each frame in operation mode T1.
speed_limit_autolimit Max allowed speed for each frame in operation mode AUTOMATIC.
set_speed_limit_funcFunction allowing to report the speed limit change to the system

Definition at line 24 of file operation_mode_setup_executor.cpp.

Member Function Documentation

bool prbt_hardware_support::OperationModeSetupExecutor::getSpeedOverride ( GetSpeedOverride::Request &  ,
GetSpeedOverride::Response &  response 
)

Definition at line 65 of file operation_mode_setup_executor.cpp.

void prbt_hardware_support::OperationModeSetupExecutor::updateOperationMode ( const OperationModes &  operation_mode)

Function to be called whenever a new operation mode is set.

Definition at line 34 of file operation_mode_setup_executor.cpp.

Member Data Documentation

SetSpeedLimitFunc prbt_hardware_support::OperationModeSetupExecutor::set_speed_limit_func_
private

Function used to propagate speed limit changes into the system.

Definition at line 73 of file operation_mode_setup_executor.h.

const double prbt_hardware_support::OperationModeSetupExecutor::speed_limit_auto_
private

The allowed speed limit in operation mode AUTOMATIC.

Definition at line 67 of file operation_mode_setup_executor.h.

const double prbt_hardware_support::OperationModeSetupExecutor::speed_limit_t1_
private

The allowed speed limit in operation mode T1.

Definition at line 65 of file operation_mode_setup_executor.h.

std::atomic<double> prbt_hardware_support::OperationModeSetupExecutor::speed_override_ {0.0}
private

The active speed override.

Definition at line 70 of file operation_mode_setup_executor.h.

ros::Time prbt_hardware_support::OperationModeSetupExecutor::time_stamp_last_op_mode_ {ros::Time(0)}
private

Time stamp of the last received operation mode.

Definition at line 75 of file operation_mode_setup_executor.h.


The documentation for this class was generated from the following files:


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