mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: log alt target from PosControl
This commit is contained in:
parent
44e731ea40
commit
e69eeea246
@ -255,7 +255,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||
control_yaw / 1.0e2f,
|
||||
wp_bearing / 1.0e2f,
|
||||
wp_distance / 1.0e2f,
|
||||
altitude_error / 1.0e2f,
|
||||
pos_control.get_alt_error() / 1.0e2f,
|
||||
0,
|
||||
0);
|
||||
}
|
||||
|
@ -325,7 +325,7 @@ static void Log_Write_Control_Tuning()
|
||||
throttle_in : g.rc_3.control_in,
|
||||
angle_boost : angle_boost,
|
||||
throttle_out : g.rc_3.servo_out,
|
||||
desired_alt : get_target_alt_for_reporting() / 100.0f,
|
||||
desired_alt : pos_control.get_alt_target() / 100.0f,
|
||||
inav_alt : current_loc.alt / 100.0f,
|
||||
baro_alt : baro_alt,
|
||||
desired_sonar_alt : (int16_t)target_sonar_alt,
|
||||
|
Loading…
Reference in New Issue
Block a user