MAV'RIC
|
Classes | |
struct | conf_t |
Configuration structure. More... | |
Public Member Functions | |
INS_AHRS_groundtruth (Dynamic_model &model, const conf_t &config=default_config()) | |
Constructor. | |
virtual bool | update (void) |
Main update function. | |
virtual float | last_update_s (void) const |
Last update of the internal values in seconds. | |
virtual local_position_t | position_lf (void) const |
3D Position in meters (NED frame) | |
virtual std::array< float, 3 > | velocity_lf (void) const |
Velocity in meters/seconds in NED frame. | |
virtual float | absolute_altitude (void) const |
Absolute altitude above sea level in meters (>=0) | |
virtual bool | is_healthy (INS::healthy_t type) const |
Indicates which estimate can be trusted (always returns true) | |
virtual bool | is_healthy (void) const |
Indicates which estimate can be trusted (always returns true) | |
quat_t | attitude (void) const |
Estimated attitude. | |
std::array< float, 3 > | angular_speed (void) const |
Estimated angular velocity. | |
std::array< float, 3 > | linear_acceleration (void) const |
Estimated linear acceleration. | |
Static Public Member Functions | |
static conf_t | default_config () |
Returns the default configuration for INS_AHRS_groundtruth. | |
Protected Attributes | |
Dynamic_model & | model_ |
Dynamic model providing position and velocity information. | |
local_position_t | position_lf_ |
local position estimation (NED in meters) | |
std::array< float, 3 > | velocity_lf_ |
local velocity estimation (NED in meters/seconds) | |
float | absolute_altitude_ |
Absolute altitude above sea level in meters (>=0) | |
quat_t | attitude_ |
Estimated attitude. | |
std::array< float, 3 > | angular_speed_ |
Estimated angular speed. | |
std::array< float, 3 > | linear_acc_ |
Estimated linear acceleration. | |
float | last_update_s_ |
time stamp of last update in seconds |
virtual float INS_AHRS_groundtruth::absolute_altitude | ( | void | ) | const [inline, virtual] |
std::array< float, 3 > INS_AHRS_groundtruth::angular_speed | ( | void | ) | const [virtual] |
quat_t INS_AHRS_groundtruth::attitude | ( | void | ) | const [virtual] |
INS_AHRS_groundtruth::conf_t INS_AHRS_groundtruth::default_config | ( | void | ) | [inline, static] |
Returns the default configuration for INS_AHRS_groundtruth.
default origin is set to ORIGIN_EPFL
virtual bool INS_AHRS_groundtruth::is_healthy | ( | INS::healthy_t | type | ) | const [inline, virtual] |
Indicates which estimate can be trusted (always returns true)
type | Type of estimate |
Implements INS.
virtual bool INS_AHRS_groundtruth::is_healthy | ( | void | ) | const [inline, virtual] |
float INS_AHRS_groundtruth::last_update_s | ( | void | ) | const [inline, virtual] |
std::array< float, 3 > INS_AHRS_groundtruth::linear_acceleration | ( | void | ) | const [virtual] |
virtual local_position_t INS_AHRS_groundtruth::position_lf | ( | void | ) | const [inline, virtual] |
bool INS_AHRS_groundtruth::update | ( | void | ) | [virtual] |
Main update function.
Update dynamic model and internally stored values
Implements AHRS.
virtual std::array<float,3> INS_AHRS_groundtruth::velocity_lf | ( | void | ) | const [inline, virtual] |