mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: Use named float wrapper
This commit is contained in:
parent
f6624cc8b2
commit
296296ab6c
@ -517,8 +517,7 @@ void Copter::ModeFlowHold::update_height_estimate(void)
|
||||
(double)ins_height,
|
||||
(double)last_ins_height,
|
||||
dt_ms);
|
||||
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, AP_HAL::millis(), "HEST", height_estimate);
|
||||
mavlink_msg_named_value_float_send(MAVLINK_COMM_1, AP_HAL::millis(), "HEST", height_estimate);
|
||||
gcs().send_named_float("HEST", height_estimate);
|
||||
delta_velocity_ne.zero();
|
||||
last_ins_height = ins_height;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user