Has anybody used GND_ALT_OFFSET using the altitude from a ground based Pixhawk to correct the altitude of a copter?
I’m seeing poor results with it over longer durations. I’m updating the copter’s GND_ALT_OFFSET every second using -1*current_gcs_altitude to help hold the copter at a constant real altitude as the barometric altitude drifts due to typical atmospheric changes during the day. Over a longer duration flight (30 minutes), the copter tends to drift down in altitude much more (5-6m) than the 1-2 m of change that I’m sending it via GND_ALT_OFFSET. If I raise the ground based PIxhawk a meter, the copter will slowly raise a meter so I believe I have the correction coded correctly.
In the past, I’ve just adjusted the waypoint by the GCS’s altitude to compensate and that worked out fairly well.
I’ve looked at the code and it appears that a change in GND_ALT_OFFSET gets added 5% at a time until its within 1 cm of the previous offset as shown here:
if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
// If there’s more than 1cm difference then slowly slew to it via LPF.
// The EKF does not like step inputs so this keeps it happy.
_alt_offset_active = (0.95f*_alt_offset_active) + (0.05f*_alt_offset);
} else {
_alt_offset_active = _alt_offset;
}
It takes about 100 iterations to converge to the target altitude. This approach looks reasonable for providing a smooth change.
I’ve thought about changing the GND_ABS_PRESS as well using the absolute pressure from the ground-based Pixhawk. Has anybody done that?
Any feedback is appreciated. (We’re looking at more accurate altitude sensors as well, but it seems like this differential barometer approach should work for compensating gross atmospheric pressure changes.)
Thanks,
Rob