MAV'RIC
Classes | Public Member Functions | Static Public Member Functions | Protected Attributes
INS_AHRS_groundtruth Class Reference
Inheritance diagram for INS_AHRS_groundtruth:
Inheritance graph
[legend]
Collaboration diagram for INS_AHRS_groundtruth:
Collaboration graph
[legend]

List of all members.

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_modelmodel_
 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

Member Function Documentation

virtual float INS_AHRS_groundtruth::absolute_altitude ( void  ) const [inline, virtual]

Absolute altitude above sea level in meters (>=0)

Value is only updated upon calling update()

Returns:
altitude [meters above sea level (>0)]

Implements INS.

std::array< float, 3 > INS_AHRS_groundtruth::angular_speed ( void  ) const [virtual]

Estimated angular velocity.

Returns:
3D angular velocity

Implements AHRS.

quat_t INS_AHRS_groundtruth::attitude ( void  ) const [virtual]

Estimated attitude.

Returns:
quaternion

Implements AHRS.

Returns the default configuration for INS_AHRS_groundtruth.

default origin is set to ORIGIN_EPFL

Returns:
config default configuration
virtual bool INS_AHRS_groundtruth::is_healthy ( INS::healthy_t  type) const [inline, virtual]

Indicates which estimate can be trusted (always returns true)

Parameters:
typeType of estimate
Returns:
boolean

Implements INS.

virtual bool INS_AHRS_groundtruth::is_healthy ( void  ) const [inline, virtual]

Indicates which estimate can be trusted (always returns true)

Returns:
boolean

Implements AHRS.

float INS_AHRS_groundtruth::last_update_s ( void  ) const [inline, virtual]

Last update of the internal values in seconds.

Value is only updated upon calling update()

Returns:
time [seconds]

Implements AHRS.

std::array< float, 3 > INS_AHRS_groundtruth::linear_acceleration ( void  ) const [virtual]

Estimated linear acceleration.

Returns:
3D linear acceleration

Implements AHRS.

virtual local_position_t INS_AHRS_groundtruth::position_lf ( void  ) const [inline, virtual]

3D Position in meters (NED frame)

Value is only updated upon calling update()

Returns:
position [NED in meters]

Implements INS.

bool INS_AHRS_groundtruth::update ( void  ) [virtual]

Main update function.

Update dynamic model and internally stored values

Returns:
Success

Implements AHRS.

Here is the call graph for this function:

virtual std::array<float,3> INS_AHRS_groundtruth::velocity_lf ( void  ) const [inline, virtual]

Velocity in meters/seconds in NED frame.

Value is only updated upon calling update()

Returns:
velocity [NED in meters/second]

Implements INS.


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines