mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: Handle NAV_CONTROLLER_OUTPUT.wp_dist overflowing
This commit is contained in:
parent
f0cb234228
commit
57c9afb77e
@ -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…
Reference in New Issue
Block a user