ardupilot/ArduCopter/inertia.cpp

28 lines
1.0 KiB
C++
Raw Normal View History

#include "Copter.h"
// read_inertia - read inertia in from accelerometers
void Copter::read_inertia()
{
2019-03-21 06:51:35 -03:00
// 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;
2016-04-19 04:16:06 -03:00
// 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
2021-10-20 05:29:57 -03:00
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);
}
}