ArduPilot / ardupilot

ArduPlane, ArduCopter, ArduRover, ArduSub source
http://ardupilot.org/
GNU General Public License v3.0
10.96k stars 17.48k forks source link

Plane steering controller doesn't reset integrator after takeoff #27563

Open jknight100 opened 3 months ago

jknight100 commented 3 months ago

Bug report

Issue details When using ground steering: Run a full auto mission with takeoff, waypoints, and landing, without changing modes to MANUAL, FBWA, etc. During landing, when steering controller is engaged at GROUND_STEER_ALT, the controller has a residual value forcing rudder to a new position. The issue is that the steering controller (not yaw controller) doesn't clear out the integrator term prior to landing. See the "PIDS" message log. However, the integrator WILL get cleared if mode is changed out of AUTO. One potential fix is to drop "plane.steerController.reset_I();" in the MAV_CMD_NAV_LAND case in commands_logic.cpp.

Version Plane 4.4.4

Platform [ ] All [ ] AntennaTracker [ ] Copter [X] Plane [ ] Rover [ ] Submarine

Airframe type Conventional fixed wing airplane with tricycle landing gear

Hardware type CubeOrange

Logs Cannot provide, but this can easily be observed by running a full mission in auto with takeoff and landing. Look at PIDS message and see that integrator term does not clear after takeoff, resumes when steering controller is active during landing when GROUND_STEER_ALT is achieved.

IamPete1 commented 3 months ago

While your correct I'm not sure if resetting would gain us much because it would start winding up as soon as your under GROUND_STEER_ALT again.

A log would be very useful.