Browse Source

Plane: Handle NAV_CONTROLLER_OUTPUT.wp_dist overflowing

mission-4.1.18
Michael du Breuil 8 years ago committed by Francisco Ferreira
parent
commit
8691eae679
  1. 2
      ArduPlane/GCS_Mavlink.cpp

2
ArduPlane/GCS_Mavlink.cpp

@ -199,7 +199,7 @@ void Plane::send_nav_controller_output(mavlink_channel_t chan) @@ -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…
Cancel
Save