@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.