mirror of https://github.com/ArduPilot/ardupilot
28 lines
1.0 KiB
C++
28 lines
1.0 KiB
C++
#include "Copter.h"
|
|
|
|
// read_inertia - read inertia in from accelerometers
|
|
void Copter::read_inertia()
|
|
{
|
|
// inertial altitude estimates. Use barometer climb rate during high vibrations
|
|
inertial_nav.update(vibration_check.high_vibes);
|
|
|
|
// pull position from ahrs
|
|
Location loc;
|
|
ahrs.get_location(loc);
|
|
current_loc.lat = loc.lat;
|
|
current_loc.lng = loc.lng;
|
|
|
|
// exit immediately if we do not have an altitude estimate
|
|
if (!inertial_nav.get_filter_status().flags.vert_pos) {
|
|
return;
|
|
}
|
|
|
|
// current_loc.alt is alt-above-home, converted from inertial nav's alt-above-ekf-origin
|
|
const int32_t alt_above_origin_cm = inertial_nav.get_position_z_up_cm();
|
|
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_ORIGIN);
|
|
if (!ahrs.home_is_set() || !current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
|
|
// if home has not been set yet we treat alt-above-origin as alt-above-home
|
|
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_HOME);
|
|
}
|
|
}
|