Skip to content
This repository has been archived by the owner on Oct 27, 2020. It is now read-only.

PIDF for goBilda 5202 very slow #150

Open
OviedoRobotics opened this issue Nov 22, 2019 · 13 comments
Open

PIDF for goBilda 5202 very slow #150

OviedoRobotics opened this issue Nov 22, 2019 · 13 comments

Comments

@OviedoRobotics
Copy link

We previously used the Matrix 12V motors for our robot config and use a goBilda 5202 1150 RPM motor for our lift. We use RUN_TO_POSITION to set out lift to encoder stone heights. With the Matrix 12V configuration this works pretty well. With SDK 5.3 we switched to goBilda 5202 motors and the lift is easily twice as slow to reach position. Needless to say, we switched back to Matrix 12V.

@gearsincorg
Copy link

I think that the PIDF values that we chose for these motors work well for low load, but they do seem to be too low for typically loaded motors.

I would suggest setting new PIDF values to get higher performance.
In our case we reverted back to the original PID values, but added in the F coefficient for good feed forward control. Our drive is much more responsive now.

This meant using PIDF values of 10.0, 3.0, 0 and 12 respectively.

We used this helper method to create and assign each of our drive motors.

Note that you have to use DcMotorEx rather than DcMotor to set the coefficients.

    // Configure a motor
    public DcMotorEx configureMotor( String motorName,  DcMotor.Direction direction) {
        PIDFCoefficients newPIDF = new PIDFCoefficients(10.0,  3.0,   0.0,  12.0);
        DcMotorEx motorObj = myOpMode.hardwareMap.get(DcMotorEx.class, motorName);

        motorObj.setDirection(direction);
        motorObj.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
        motorObj.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, newPIDF);
        return motorObj;
    }

ps: The 1150 RPM goBILDA motor is probably faster than the matrix (under no load), but much lower torque, so if your lift is a significant load, you may be exceeding the motor's torque capability, which may also be causing it to run slow. (but it's probably also the PIDF :)

@Windwoes
Copy link
Member

@gearsincorg the original default D coefficient was 0? That effectively makes it a "PIF" controller.....

@AustinShalit
Copy link
Member

Maybe the controller needs more position P if it is moving too slowly when close to the target

@rischconsulting
Copy link

I'll make sure they test this, but I'm skeptical:

  1. I think they did
  2. Many teams are experiencing this
  3. They already attempted a fix by increasing velocity, as well as velocity P and velocity I, and had to tune Position P down from the suggested 5 to 2 in order to not get it to overshoot (and then move very slowly backward to correct the error).

@AustinShalit
Copy link
Member

The best way to test the velocity PIDF constants is to run motors in velocity mode logging the set point vs the current velocity. If these mostly match up, then the only change to make is in the position controller.

@OviedoRobotics
Copy link
Author

I think that the PIDF values that we chose for these motors work well for low load, but they do seem to be too low for typically loaded motors.

I would suggest setting new PIDF values to get higher performance.
In our case we reverted back to the original PID values, but added in the F coefficient for good feed forward control. Our drive is much more responsive now.

This meant using PIDF values of 10.0, 3.0, 0 and 12 respectively.

We used this helper method to create and assign each of our drive motors.

Note that you have to use DcMotorEx rather than DcMotor to set the coefficients.

    // Configure a motor
    public DcMotorEx configureMotor( String motorName,  DcMotor.Direction direction) {
        PIDFCoefficients newPIDF = new PIDFCoefficients(10.0,  3.0,   0.0,  12.0);
        DcMotorEx motorObj = myOpMode.hardwareMap.get(DcMotorEx.class, motorName);

        motorObj.setDirection(direction);
        motorObj.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
        motorObj.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, newPIDF);
        return motorObj;
    }

ps: The 1150 RPM goBILDA motor is probably faster than the matrix (under no load), but much lower torque, so if your lift is a significant load, you may be exceeding the motor's torque capability, which may also be causing it to run slow. (but it's probably also the PIDF :)

I think perhaps you misunderstood. We are always using a gobilda 5202 1150 RPM motor. But if we configure it as a Matrix 12v the lift RUN TO POSITION works WAY better. If we configure it as goBilda 5202, the assessment others give is dead on. It takes forever to reach near the set point as it gets really slow during fine adjustment. I think we are looking for +/- 20 encoder counts and there are several seconds difference for the two configs.

@gearsincorg
Copy link

Oh yeah, that wasn't totally clear from the original post... Same motor.. different config. Gotcha.

There are no PIF defaults set for the MATRIX motor, so by selecting it, you end up with the original PID algorithm, and coefficients.

Generally speaking, the transition speed will be set by the Velocity PIDF, and the final approach will be controlled by the Position PIDF, (which only uses the P term).

@rischconsulting
Copy link

OK, for the record, we tested this today. We upped Position P to 12.5 and got better results. We still have some tuning to do, but this is working better. I think adjusting the guide (which says to start with 5) might be helpful, as that seems to be throwing a lot of people off.

@OviedoRobotics
Copy link
Author

Is there an FTC guide for setting up the hub PIDF parameters?

@Windwoes
Copy link
Member

Windwoes commented Dec 8, 2019

When using the default PIDF parameters with a NeveRest20 (and configured as NeveRest20) I also get very bad results, on a heavily loaded motor anyway. Not only does the PIDF take forever to get to the target if it's a small movement, but it will many times overshoot if it's a big movement! Switching to the legacy PID yielded much better results - responsive movement even if it's only a small amount, and it does not seem to overshoot.

@rischconsulting
Copy link

Now that 5.4 is reverting, it's unclear what we should be doing given that the motorex code still asks for PIDF. Anyone have an idea of what we should do? Just leave F as 0 and treat it as straight PID?

@gearsincorg
Copy link

With 5.4, if you don't explicitly set PIDF coefficients, the controller will run the legacy control algorithms with the legacy PID coefficients.

Once you do set PIDF coefficients, it will run the PIDF control algorithm (unless you switch back to PID coefficients).

The PID methods do show up as deprecated, but they still work as before, so there is no "requirement" to use PIDF for DCMotor, or DCMotorEx

So you have several options:

  1. Don't make any PIDF calls, and you will get legacy (PID) behavior.
    or
  2. Make PIDF calls to set coefficients but just re-load the original PID coefficients with an F term of zero. In theory, the control will behave very similarly.
    or
  3. Make PIDF calls to set coefficients. Load your own combination of coefficients based on your own robot & testing.

For expediency, my team is using option 1.

Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

No branches or pull requests

5 participants