Configuration structure for LocalPositionAssessor, defines default acceptance criteria for local position threshold-checkers.
More...
#include <auterion_sdk/system_state/local_position_assessor.hpp>
Configuration structure for LocalPositionAssessor, defines default acceptance criteria for local position threshold-checkers.
- See also
- LocalPositionAssessor
◆ withAccelerationThreshold()
LocalPositionAssessorConfig& auterion::LocalPositionAssessorConfig::withAccelerationThreshold |
( |
const float |
absolute_acceleration_threshold_m_s2 | ) |
|
|
inline |
Set the absolute acceleration threshold.
- Parameters
-
absolute_acceleration_threshold_m_s2 | The desired absolute acceleration threshold [m/s^2]. |
- Returns
- Reference to the modified LocalPositionAssessorConfig.
◆ withHeadingErrorThreshold()
LocalPositionAssessorConfig& auterion::LocalPositionAssessorConfig::withHeadingErrorThreshold |
( |
const float |
heading_error_threshold_rad | ) |
|
|
inline |
Set the heading error threshold.
- Parameters
-
heading_error_threshold_rad | The desired heading error threshold [rad]. |
- Returns
- Reference to the modified LocalPositionAssessorConfig.
◆ withPositionErrorThreshold()
LocalPositionAssessorConfig& auterion::LocalPositionAssessorConfig::withPositionErrorThreshold |
( |
const float |
position_error_threshold_m | ) |
|
|
inline |
Set the position error threshold.
- Parameters
-
position_error_threshold_m | The desired position error threshold [m]. |
- Returns
- Reference to the modified LocalPositionAssessorConfig.
◆ withVelocityThreshold()
LocalPositionAssessorConfig& auterion::LocalPositionAssessorConfig::withVelocityThreshold |
( |
const float |
absolute_velocity_threshold_m_s | ) |
|
|
inline |
Set the absolute velocity threshold.
- Parameters
-
absolute_velocity_threshold_m_s | The desired absolute velocity threshold [m/s]. |
- Returns
- Reference to the modified LocalPositionAssessorConfig.
◆ absolute_acceleration_threshold_m_s2
float auterion::LocalPositionAssessorConfig::absolute_acceleration_threshold_m_s2 |
Initial value:Absolute acceleration threshold [m/s^2].
◆ absolute_velocity_threshold_m_s
float auterion::LocalPositionAssessorConfig::absolute_velocity_threshold_m_s {0.3F} |
Absolute velocity threshold [m/s].
◆ heading_error_threshold_rad
float auterion::LocalPositionAssessorConfig::heading_error_threshold_rad {7.F * M_PI / 180.F} |
Heading error threshold [rad].
◆ position_error_threshold_m
float auterion::LocalPositionAssessorConfig::position_error_threshold_m {0.5F} |
Position error threshold [m].
The documentation for this struct was generated from the following file: