Skid steering in reverse

I just began evaluating ArduRover for a possible boat application. Before selecting hardware, I have chosen to user apmplanner2 (2.0.24), SITL, and MAVProxy to learn about the rover software. Just to confirm, I am running 3.1.0 software. I created a mission with several waypoints, the last being a final destination. Before the last waypoint, I inserted a DO_SET_REVERSE command.

When I run the mission with the default rover.parm file, the mission runs fine. When I run it with the rover-skid.parm file, it arrives and the next to last WP, switches to reverse, orients the rover properly and then crashes before proceeding to the final waypoint,

As far as I can tell, the parm files only differ in the value of SKID_STEER_OUT=1.

Picture a rover navigating through a parking lot, arriving at a WP in front of a parking spot, changing to reverse and backing into the parking spot as the final WP.

I tried reducing the speed to 0 before the DO_SET_REVERSE, and back up to speed after. It stilled crashed.

Am I missing something fundamental? Still learning about the logs, so input would be appreciated.

Fred

Update.

Having delved into the logs, I have discovered that the crash resulted from oscillations on the RC1 and RC3 outputs, they toggle back and forth between 1250 and 1750. Each is one step out of phase with the other. The rover just sits there and twitches and does not change position.

Correspondingly, these values also oscillate in the same fashion:

ATT.Yaw oscillates 357 - 1
CTUN.Steert oscillates -2250 - +2250
CTUN.Throut oscillates -50 - +50
NTUN.Yaw oscillates wildly
NTUN.Thr oscillates -50 - +50
C1 oscillates 1750 - 1250
C3 oscillates 1250 - 1750

I have tried various values for these parameters to no avail:
STEER2SRV_P
STEER2SRV_I
STEER2SRV_D
STEER2SRV_IddMAX
STEER2SRV_IMAX
STEER2SRV_MINSPD
STEER2SRV_TCONST
THR_SLEWRATE
THR_MAX
TURN_MAX_G
NAVL1_DAMPING
NAVL1_PERIOD
PIVOT_TURN_ANGLE

Is there a fundamental flaw with skid steering in reverse?
Fred

Solved I think.

Switching to reverse during a rover mission using skid steering, required that I set PIVOT_TURN_ANGLE to something reasonable. A value of 5 works for me. So, while going to reverse, the rover performs a pivot turn.

In ardupilot/APMrover/Steering.cpp, the method calc_throttle() calls the method use_pivot_steering() as such and sets the throttle servo to 0 to complete the turn.

if (use_pivot_steering()) {
    channel_throttle->set_servo_out(0);
}

The use_pivot_steering() method compares the bearing_error to the pivot_turn_angle and if exceeded, returns true to initiate or continue a pivot turn.

if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) {
    int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;

    if (abs(bearing_error) > g.pivot_turn_angle) {
        return true;
    }
}
return false;

The problem is that the rover has reversed and the bearing_error will remain close to 180, causing the calc_throttle() code to remain in pivot steering mode and continuing to set the throttle servo to 0. Thus the rover remains stationary.

I would propose a change to the use_pivot_steering() method to treat the pivot_turn_angle differently in reverse. While in reverse, the bearing error should be compared to a value of 180 - pivot_turn_angle to compensate for being in reverse. I have performed limited testing on the code below and it works for me when using SITL.

if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) {
    int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;

    if (in_reverse) {
        if (abs(bearing_error) < abs(180 - g.pivot_turn_angle)) {
            return true;
        } else {
            return false;
        }
    } else if (abs(bearing_error) > g.pivot_turn_angle) {
        return true;
    }
}
return false;

There is another call to use_pivot_steering() used while calculating lateral_acceleration. I am not familiar enough with this part of the code to assess the impact of my proposed change. Perhaps someone else with more experience could do so.

Fred

Update

There doesn’t seem to be much interest in this topic. Could someone suggest where I might post to get some further attention and possibly a software change?

The real culprit turns out to be use of ahrs.yaw_sensor while in reverse using skid steering. Both AP_Navigation and AP_L1_Controller libraries are aware of the reverse condition and adjust yaw_sensor by 180 degrees accordingly. The rover 3.1.0 Steering.cpp does not.

After adjusting for this where yaw-sensor is used, a problem still exists. Consider a mission: Home at WP0, WP1, DO_SET_REVERSE, WP2, WP3, where all WPs are in a straight line.

The rover will not find WP2 and WP3 unless PIVOT_TURN_ANGLE is set. If set, it finds WP1 fine with very little oscillation of the two motor outputs. After changing to reverse, the steering becomes very sloppy with oscillations of the motor outputs.

Increasing the PIVOT_TURN_ANGLE just allows the rover to wander further off course. Decreasing the PIVOT_TURN_ANGLE just increases the oscillation due to the pivot steering turn angle being based on lateral acceleration divided by speed.

Anyone have any further ideas?

@rainwf,
Try here
Regards,
TCIII AVD

Hello !

Sorry for the long delay, I see your post but don’t reply until now. Be aware that there aren’t many developper on Rover currently : Me and @gmorph . So it goes slowly on rover …

I never try reverse yet. I will try to reproduce the bug and look at the problem and your solution this week or the next week

Ok I have reproduce the bug on sitl with you indication!
In fact, it get stuck in skid steer or consider it crash (you can disable the FS_CRASH_CHECK) as throttle is applied and the rover doesn’t move !

Your solution looks like good . Do you know how to make a pull request ? or do you want me to make it (with credit to you, of course!)

Thanks so much for your quick response. I did disable FS_CRASH_CHECK to make progress. I have continued to investigate. I am into the L1 control code just now. I have observed a couple of additional potential issues. The file AP_L1_Control.cpp has several references to _ahrs.yaw and _ahrs.yaw_sensor without recognizing the reverse condition. The included methods get_yaw() and get_yaw_sensor() both correct for the reverse condition. Should not all AP_L1_Control.cpp code use these methods?

I have concluded that enabling PIVOT_TURN_ANGLE with a relatively small angle is the only way to follow waypoints in a line and change to reverse and come close to following the straight line. Its not perfect though and the L1 cross track error results in lateral acceleration to reduce the cross track error which then produces a bearing error that exceeds the PIVOT_TURN_ANGLE. This then initiates a pivot turn with a reverse lateral acceleration that is proportional to TURN_MAX_G/speed. When bearing_error is again below PIVOT_TURN_ANGLE, the cross track lateral acceleration is again applied until PIVOT_TURN_ANGLE is again exceeded and the whole process repeats. This oscillation results in the motor outputs switching back and forth in an unacceptable manner.

For reference, I have disabled NAVL1_XTRACK_I and set TURN_MAX_G to the minimum. I also modified the SITL/SIM_Rover.cpp value of skid_turn_rate to 10 degrees/second which is perhaps more applicable to a boat than a rover.

Having said all this, I would suggest that you have a look at AP_L1_Control.cpp for the reverse yaw issues and share your thoughts. There is enough magic there that I would not dare to touch the code.

I would also ask if you have further thoughts on reducing the oscillation while skid steering in reverse.

And finally, would you recommend that I continue this thread on a different venue, such as the github developers forum?

Update

I was able to reduce the oscillations after the turn greatly by setting NAVL1_PERIOD to a higher value of 30. This seems to allow the rover to perform the way I want. I had changed the value earlier in an attempt to solve the yaw_sensor issue, but I had not tested changes after. A review of the parameters reminded me to experiment with tuning and it worked.

Thanks so much for your quick response. I did disable FS_CRASH_CHECK to
make progress. I have continued to investigate. I am into the L1 control
code just now. I have observed a couple of additional potential issues.
The file AP_L1_Control.cpp has several references to _ahrs.yaw and
_ahrs.yaw_sensor without recognizing the reverse condition. The included
methods get_yaw() and get_yaw_sensor() both correct for the reverse
condition. Should not all AP_L1_Control.cpp code use these methods?

I have concluded that enabling PIVOT_TURN_ANGLE with a relatively small
angle is the only way to follow waypoints in a line and change to reverse
and come close to following the straight line. Its not perfect though and
the L1 cross track error results in lateral acceleration to reduce the
cross track error which then produces a bearing error that exceeds the
PIVOT_TURN_ANGLE. This then initiates a pivot turn with a reverse lateral
acceleration that is proportional to TURN_MAX_G/speed. When bearing_error
is again below PIVOT_TURN_ANGLE, the cross track lateral acceleration is
again applied until PIVOT_TURN_ANGLE is again exceeded and the whole
process repeats. This oscillation results in the motor outputs switching
back and forth in an unacceptable manner.

For reference, I have disabled NAVL1_XTRACK_I and set TURN_MAX_G to the
minimum. I also modified the SITL/SIM_Rover.cpp value of skid_turn_rate to
10 degrees/second which is perhaps more applicable to a boat than a rover.

Having said all this, I would suggest that you have a look at
AP_L1_Control.cpp for the reverse yaw issues and share your thoughts.
There is enough magic there that I would not dare to touch the code.

I would also ask if you have further thoughts on reducing the oscillation
while skid steering in reverse.

And finally, would you recommend that I continue this thread on a different
venue, such as the github developers forum?

Fred - great investigations. I can actually replicate this issue without having to go into Reverse. khancyr has kindly raised the issue here:


and this is now my top priority to fix as it would appear skid steering is busted.

Thanks, Grant.