APM:Copter
inertia.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // read_inertia - read inertia in from accelerometers
5 {
6  // inertial altitude estimates
8 
9  // pull position from interial nav library
12 
13  // exit immediately if we do not have an altitude estimate
15  return;
16  }
17 
18  // without home return alt above the EKF origin
19  if (!ahrs.home_is_set()) {
20  // with inertial nav we can update the altitude and climb rate at 50hz
22  } else {
23  // with inertial nav we can update the altitude and climb rate at 50hz
25  }
26 
27  // set flags and get velocity
30 }
float get_velocity_z() const
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
void read_inertia()
Definition: inertia.cpp:4
float get_altitude() const
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
int32_t lat
nav_filter_status get_filter_status() const
int32_t alt
int32_t get_latitude() const
Location_Class current_loc
Definition: Copter.h:475
float pv_alt_above_home(float alt_above_origin_cm)
Location_Option_Flags flags
struct nav_filter_status::@138 flags
int16_t climb_rate
Definition: Copter.h:464
int32_t lng
void update(float dt)
bool home_is_set(void) const
int32_t get_longitude() const
float G_Dt
Definition: Copter.h:480