Class for assessing various properties of LocalPosition objects.
More...
#include <auterion_sdk/system_state/local_position_assessor.hpp>
Class for assessing various properties of LocalPosition objects.
- See also
- auterion::LocalPosition
◆ LocalPositionAssessor()
◆ isAccelerationUnderThreshold()
bool auterion::LocalPositionAssessor::isAccelerationUnderThreshold |
( |
const std::optional< float > |
absolute_acceleration_threshold_m_s2 = std::nullopt | ) |
const |
Check if the current acceleration is under the specified threshold.
- Parameters
-
absolute_acceleration_threshold_m_s2 | Absolute acceleration threshold [m/s^2] (optional). |
- Returns
- True if the acceleration is under the threshold, false otherwise.
◆ isHeadingWithinThreshold()
bool auterion::LocalPositionAssessor::isHeadingWithinThreshold |
( |
const float |
target_heading_enu_rad, |
|
|
const std::optional< float > |
heading_error_threshold_rad = std::nullopt |
|
) |
| const |
Check if the current heading is within specified thresholds of the target heading.
- Parameters
-
target_heading_enu_rad | Target heading [rad]. |
heading_error_threshold_rad | Heading error threshold [rad] (optional). |
- Returns
- True if the heading is within threshold, false otherwise.
◆ isPositionWithinThreshold()
bool auterion::LocalPositionAssessor::isPositionWithinThreshold |
( |
const Eigen::Vector3f & |
target_local_position_m, |
|
|
const std::optional< float > |
position_error_threshold_m = std::nullopt |
|
) |
| const |
Check if the current position is within specified thresholds of the target location.
- Parameters
-
target_local_position_m | Target local position [m]. |
position_error_threshold_m | Position error threshold [m] (optional). |
- Returns
- True if the position is within threshold, false otherwise.
◆ isVelocityUnderThreshold()
bool auterion::LocalPositionAssessor::isVelocityUnderThreshold |
( |
const std::optional< float > |
absolute_velocity_threshold_m_s = std::nullopt | ) |
const |
Check if the current velocity is under the specified threshold.
- Parameters
-
absolute_velocity_threshold_m_s | Absolute velocity threshold [m/s] (optional). |
- Returns
- True if the velocity is under the threshold, false otherwise.
The documentation for this class was generated from the following file: