mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: Handle NAV_CONTROLLER_OUTPUT.wp_dist overflowing
This commit is contained in:
parent
bc8c13d053
commit
8691eae679
@ -199,7 +199,7 @@ void Plane::send_nav_controller_output(mavlink_channel_t chan)
|
||||
nav_pitch_cd * 0.01f,
|
||||
nav_controller->nav_bearing_cd() * 0.01f,
|
||||
nav_controller->target_bearing_cd() * 0.01f,
|
||||
auto_state.wp_distance,
|
||||
MIN(auto_state.wp_distance, UINT16_MAX),
|
||||
altitude_error_cm * 0.01f,
|
||||
airspeed_error * 100,
|
||||
nav_controller->crosstrack_error());
|
||||
|
Loading…
Reference in New Issue
Block a user