APM:Libraries
|
#include <AP_InertialNav.h>
Public Member Functions | |
AP_InertialNav () | |
virtual void | update (float dt)=0 |
virtual nav_filter_status | get_filter_status () const =0 |
virtual struct Location | get_origin () const =0 |
virtual const Vector3f & | get_position () const =0 |
virtual bool | get_location (struct Location &loc) const =0 |
virtual int32_t | get_latitude () const =0 |
virtual int32_t | get_longitude () const =0 |
virtual const Vector3f & | get_velocity () const =0 |
virtual float | get_velocity_xy () const =0 |
virtual float | get_altitude () const =0 |
virtual float | get_velocity_z () const =0 |
Definition at line 23 of file AP_InertialNav.h.
|
inline |
|
pure virtual |
get_altitude - get latest altitude estimate in cm above the reference position
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav(), AC_PosControl::get_alt_error(), AC_PosControl::get_stopping_point_z(), AC_WPNav::get_terrain_offset(), AC_PosControl::relax_alt_hold_controllers(), AC_PosControl::run_z_controller(), AC_PosControl::set_alt_target_to_current_alt(), and AC_PosControl::set_alt_target_with_slew().
|
pure virtual |
get_filter_status : returns filter status as a series of flags
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav().
|
pure virtual |
get_latitude - returns the latitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav().
|
pure virtual |
get_llh - updates the provided location with the latest calculated location including absolute altitude returns true on success (i.e. the EKF knows it's latest position), false on failure
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav().
|
pure virtual |
get_longitude - returns the longitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav().
|
pure virtual |
get_origin - returns the inertial navigation origin in lat/lon/alt
Implemented in AP_InertialNav_NavEKF.
|
pure virtual |
get_position - returns the current position relative to the home location in cm.
Implemented in AP_InertialNav_NavEKF.
Referenced by AC_WPNav::advance_spline_target_along_track(), AC_WPNav::advance_wp_target_along_track(), AP_InertialNav(), AC_PosControl::get_bearing_to_target(), AC_Circle::get_closest_point_on_circle(), AC_PosControl::get_stopping_point_xy(), AC_WPNav::get_wp_bearing_to_destination(), AC_WPNav::get_wp_distance_to_destination(), AC_Circle::init_start_angle(), AC_PosControl::init_takeoff(), AC_Loiter::init_target(), AC_PosControl::init_vel_controller_xyz(), AC_PosControl::run_xy_controller(), AC_WPNav::shift_wp_origin_to_current_pos(), AC_Loiter::soften_for_landing(), and AC_PosControl::write_log().
|
pure virtual |
get_velocity - returns the current velocity in cm/s
Implemented in AP_InertialNav_NavEKF.
Referenced by AC_WPNav::advance_wp_target_along_track(), AP_InertialNav(), AC_PosControl::get_stopping_point_xy(), AC_WPNav::init_brake_target(), AC_Loiter::init_target(), AC_PosControl::init_vel_controller_xyz(), AC_PosControl::run_xy_controller(), AC_PosControl::run_z_controller(), AC_WPNav::set_wp_origin_and_destination(), and AC_PosControl::write_log().
|
pure virtual |
get_velocity_xy - returns the current horizontal velocity in cm/s
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav().
|
pure virtual |
get_velocity_z - returns the current climbrate.
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav(), AC_PosControl::get_stopping_point_z(), and AC_PosControl::relax_alt_hold_controllers().
|
pure virtual |
update - updates velocity and position estimates using latest info from accelerometers augmented with gps and baro readings
dt | : time since last update in seconds |
Implemented in AP_InertialNav_NavEKF.
Referenced by AP_InertialNav().