Browse Source

Rover: Handle NAV_CONTROLLER_OUTPUT.wp_dist overflowing

mission-4.1.18
Michael du Breuil 8 years ago committed by Francisco Ferreira
parent
commit
57c9afb77e
  1. 2
      APMrover2/GCS_Mavlink.cpp

2
APMrover2/GCS_Mavlink.cpp

@ -144,7 +144,7 @@ void Rover::send_nav_controller_output(mavlink_channel_t chan) @@ -144,7 +144,7 @@ void Rover::send_nav_controller_output(mavlink_channel_t chan)
ahrs.groundspeed() * ins.get_gyro().z, // use nav_pitch to hold actual Y accel
nav_controller->nav_bearing_cd() * 0.01f,
nav_controller->target_bearing_cd() * 0.01f,
wp_distance,
MIN(wp_distance, UINT16_MAX),
0,
groundspeed_error,
nav_controller->crosstrack_error());

Loading…
Cancel
Save