Understanding history and logic of MOT_SPD_SCA_BASE

I’m trying to understand how the MOT_SPD_SCA_BASE parameter is supposed to be used.

What I see is that when I run at high speed, I get significant undershoot on achieved steering and it looks like this is to blame. However, if I disable it, then there’s massive OVERshoot.

What is it in the FF and PID logic that causes the FF mapping not to work across the speed range?

This is manifesting as an inability to follow path at higher speed.

Hi @mroberts,

In general it is best to leave that parameter at the default of 1 (m/s). The idea is that steering response increases linearly with the vehicle’s speed. So if the vehicle’s speed is doubled, only 1/2 the steering deflection is required to achieve the same turn rate.

The Ackerman steering turn rate controller also assumes that doubling the PWM output to the steering channel results in twice the turn rate. So the vehicle should turn twice as quickly when the steering servo is at its maximum (e.g. output PWM = ~2000) compared with when it is 1/2 way (e.g. PWM = ~1750).

How fast is the vehicle and do you have any logs I could look at?

At this point a random guess of what might help is to increase the MOT_SPD_SCA_BASE to 2 and re-tune the vehicle (or just drop the ATC_STR_RAT_FF by half as a starting point).

1 Like

@rmackay9 Would that be worth tweaking on boat since its turn rate is not linier?

Thanks @rmackay9, I’d misunderstood the need for that parameter so had set it to zero.

Sounds like I need to invest more time in tuning the FF and P gain through ACRO mode. Should they scale up together - i.e. if my FF is 4 or 5 (turning circle radius of 5m), then a P gain of 3-4 might reasonable? The nominal limits in the code seem to be based around smaller vehicles.

I will see what I can do with the logs - they’re long runs so can be quite sizeable.

What’s the underlying maths for the controller?

Is it output = desired_rate * FF + rate_error * P + rate_error_rate * D where the rate and error are in radians / sec and the output is -1 → 0 → 1 ?

@mroberts,

Yes, I think P and I normally scales with FF. I’ve often found that setting P and I to about 20% of FF works but higher values may also work.

The maths for the controller are like you say.

@geofrancis,

Txs for the question. Is a boat’s turn rate non-linear? … and is it different from an ackerman steering rover? In any case, I suspect you’re right that it could be improved and I did put some effort into this for vectored thrust boats and it definitely improved control.

@rmackay9 I think the turning rate will vary wildly with the boat design, for something small with an outboard it probably will be close to linier since there is very little resistance to rotation and it has a lot of control force but once you get up to something much longer, heavier with a deeper keel with smaller control surfaces I think the turning rate is going to be more or less the same even as the speed increases and will depend more on motor thrust pushing on the rudder than the vehicle speed since its not really the water flow from the boat travelling that’s pushing on the rudder but the thrust from the propeller.

http://shipsbusiness.com/turning-circle-factors.html

1 Like

@geofrancis,

Thanks for the reference. Currently we’ve got the default speed based scaling and the thrust based spacing methods (aka vectored thrust). I’ve certainly thought that at some point we may need a mix of these two methods (e.g. some boat motors have a fin on the bottom so they provide some turning thrust even if the motor isn’t spinning) but so far I haven’t bumped into a vehicle that couldn’t be tuned using either of these two separate methods… but if we do find one then I’m certainly happy to try and make it better somehow.

1 Like

A motor sailing boat would need both methods ideally, since when sailing it would be purely speed based scaling, but when motoring you would want to scale down the rudder movements at low speed since adding the throttle would massively increase the rudder authority.

How would arduboat handle a waterjet? Without throttle they have zero steering authority.

@geofrancis,

I think a waterjet should work with the vectored thrust. This feature adjusts the steering based upon the desired turn value (-1 to +1) and the current throttle output. So if the throttle is very high it will move the steering closer to the center, if the throttle is very low it will deflect the steering more. This feature does not increase the throttle in order to improve the steering response though… so if the throttle is reduced to zero for whatever reason it can’t steer.

1 Like

What about some kind of throttle rudder mix where it progressively adds a set percent of the motor with the rudder if the throttle is set at zero. It would help with drives like waterjets or anything with vectored thrust thats ineffective at steering without some thrust from the motor. you could get into the scenario with a water jet where you cut the throttle and turn to avoid something and nothing will happen, it will just go straight on since your essentially cutting off the steering with the motor.

essentially this in a parameter

1 Like

@rmackay9 we went back out today and retried the tuning. I think I’ve found a problem in the code.

When I set MOT_SPD_SCA_BASE to 1, I couldn’t get more than 10deg/s yaw rate, regardless of FF and ACRO_MAX. Jumping M_S_S_B to 2 got me 20deg/s and 3 got me up to 30deg/s, but at low speeds up to about double M_S_S_B, was getting massive overshoot at lower commanded turn rates.

I think I’ve worked out what may be causing the problems. I have a rover with a 5m turning circle radius, so ATC_STR_FF is set to 5 or more. At 20+ deg/s, even at low speeds (<5m/s), the reported FF contribution (pidFF) is between 2 and 4. That corresponds to 200 to 400% steering, right?

Mode.cpp line 494:

void Mode::set_steering(float steering_value)
{
    if (allows_stick_mixing() && g2.stick_mixing > 0) {
        steering_value = channel_steer->stick_mixing((int16_t)steering_value);
    }
    steering_value = constrain_float(steering_value, -4500.0f, 4500.0f);
    g2.motors.set_steering(steering_value);
}

This set_steering function appears to be called by ACRO and AUTO mode after calls to determine the steering_out from the attitude controller (see mode_acro.cpp ModeAcro::update() line 37 onwards.

What concerns me is that the output is being clipped at 4500 BEFORE it’s being divided by (M_S_S_B / speed) in AP_MotorsUGV. This has a significant effect if you’re ending up with a pidFF alone or pdff+pidP+pidI+pidD > 1. since it gets cut back to 1, THEN divided, rather than dividing the actual result.

This seems to match up with my observation that maximum servo output seems to be clipped at MOT_SPD_SCA_BASE / Current_Speed - i.e. if M_S_S_B is 2, and I’m travelling at 4m/s, I can never get more than half steering. That would explain why I’m seeing a consistent undershoot at higher yaw rates above M_S_S_B speed.

AP_MotorsUGV.h line 44:

// get or set steering as a value from -4500 to +4500
   //   apply_scaling should be set to false for manual modes where
   //   no scaling by speed or angle should e performed
   float get_steering() const { return _steering; }
   void set_steering(float steering, bool apply_scaling = true);

AP_MotorsUGV.cpp line 675

 // scale steering down as speed increase above MOT_SPD_SCA_BASE (1 m/s default)
                if (is_positive(_speed_scale_base) && (fabsf(ground_speed) > _speed_scale_base)) {
                    steering *= (_speed_scale_base / fabsf(ground_speed));
                } else {
                    // regular steering rover at low speed so set limits to stop I-term build-up in controllers
                    if (!have_skid_steering()) {
                        limit.steer_left = true;
                        limit.steer_right = true;
                    }
                }

I think the constrain to 4500 should be moved to the Motors library, rather than the steering output, OR only apply the clipping if you’re doing a non-scaled output (such as in MANUAL).

If you want to observe this, modify the rover in simulation to have a turning circle of 10+m - that will drive a big enough FF gain that you’ll start to see the effect.

Also, are you able to explain the effect of the second part of the if statement above - setting the “limit.steer_left” and “right” to TRUE?

Here’s an image from a simulation - turning circle 10m, ATC_STR_RAT_FF = 10.0, MOT_SPD_SCA_BASE = 1. At 20m/s, note that the absolute max commanded steering is only 1475. That corresponds to 1/20th of the steering travel.

Same at 10m/s - 1/10th of maximim travel despite the high pidFF contribution.

2 Likes

Hi @mroberts,

Thanks for looking into this in such detail. I think you may be right and I vague remember being concerned that very high speed boats would struggle as they lost the available steering range but I can’t see to find any issue on the issues list covering this so I think we just lost track of it.

As you suggest, I think we should move the constraint into the motors library.

I’ve created an issue here, thanks!

1 Like

Thanks for the review.

Funnily enough, I think the motors library already runs the constrain at the end, so it might not even be a move - just a delete of the unnecessary constrain.

I’ll fix it in my branch and see how it goes.

2 Likes

Also: looks like it’s a problem in ACRO (which calls the Mode:set_steering function), but not AUTO, which uses Mode::calc_steering_from_turn_rate which calls the g2.motors.set_steering directly.

// calculate steering output given a turn rate // desired turn rate in radians/sec. Positive to the right. void Mode::calc_steering_from_turn_rate(float turn_rate) { // calculate and send final steering command to motor library const float steering_out = attitude_control.get_steering_out_rate(turn_rate, g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt); g2.motors.set_steering(steering_out * 4500.0f); }

So AUTO is theoretically fine, except that you can’t do a good job of tuning your steering controller in ACRO mode, which I think hurts higher speed performance.

1 Like

@rmackay9 another challenge I can see is that both the maximum turn rate and the maximum steering acceleration rate (rate of change of turn rate) should both vary based on speed.

In particular, limiting the acceleration based on actuator slew is important for preventing I term build-up (I think), but since it’s variable, you can’t really set a limit without also picking a speed (and potentially affecting performance off that speed).

Max turn rate is less of an issue - either you’re capped by turn_max_g, in which case the desired will get pulled back by the system, or you’re travel-limited at low speed, and if you max your travel it appears the system automatically inhibits I-term build up.

And IMAX also might get broken by the speed scaling - an IMAX of 1.0 at 1m/s effectively becomes 0.1 at 10m/s. Maybe this does make sense though - your I gain will always give you a constant maximum rate change, and you probably don’t want the I putting in 100% steering at high speed.

1 Like

@mroberts,

I’ve created a PR to fix this issue (I think) https://github.com/ArduPilot/ardupilot/pull/20084. Any and all feedback is very welcome!

Thanks again for finding this issue and pointing me right at the fix.

1 Like