Browse Source

AP_L1: update constraint Nu comment to match sourcecode

fixes https://github.com/ArduPilot/ardupilot/issues/7054
mission-4.1.18
Tom Pittenger 7 years ago committed by GitHub
parent
commit
39dc608bea
  1. 2
      libraries/AP_L1_Control/AP_L1_Control.cpp

2
libraries/AP_L1_Control/AP_L1_Control.cpp

@ -316,7 +316,7 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct @@ -316,7 +316,7 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
_prevent_indecision(Nu);
_last_Nu = Nu;
//Limit Nu to +-pi
//Limit Nu to +-(pi/2)
Nu = constrain_float(Nu, -1.5708f, +1.5708f);
_latAccDem = K_L1 * groundSpeed * groundSpeed / _L1_dist * sinf(Nu);

Loading…
Cancel
Save