Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Retune PID controllers for DOF #85

Draft
wants to merge 6 commits into
base: development
Choose a base branch
from

Conversation

supertom01
Copy link
Member

We initially had the idea that a robot would need different PID values for high and low speeds (which is still the case but has gotten a bit out of scope of this PR right now).

The PID values have been re-tuned such that each robot can drive on high and low velocities and actually achieves them!

The robot only drives now on error whereas previously it would add the result from the PID controller to the instruction, it no longer needs this in order to operate, which is a good thing.

However as said before, the PID values for higher velocities should be made a bit more agressive, such that the robots achieve their speeds a bit faster.

This code has been tested on the field during RC2023, by both @umer99roboteam and me.

Copy link
Contributor

@skaeringur97 skaeringur97 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks like the only change wanted from this PR is taking away the + in stateLocalRef and the tuning of the PID´s. That should be a different PR since this one is about switching gains depending on velocity. If this is merged, we are switching between the same gains for different values. Meaning, computational time for no effect.

#define MIN_CHIP_TIME 10 // minimum time [ms] period of chipping
#define MAX_CHIP_TIME 100 // maximum time [ms] period of chipping
#define MIN_CHIP_TIME 110 // minimum time [ms] period of chipping
#define MAX_CHIP_TIME 110 // maximum time [ms] period of chipping
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe have this in a different PR?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Whoops that's my bad

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Has this been reverted?

stateLocalRef[vel_w] += PID(velwErr, &stateLocalK[vel_w]);
stateLocalRef[vel_u] = PID(veluErr, &stateLocalK[vel_u]);
stateLocalRef[vel_v] = PID(velvErr, &stateLocalK[vel_v]);
stateLocalRef[vel_w] = PID(velwErr, &stateLocalK[vel_w]);

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This changes the control from a feedforward to pure PID control. Might make it less stable. Make sure to test with AI if you want to go this way.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes you're right. In the end pure PID is not desirable.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Has this been tested / reverted?

@supertom01 supertom01 marked this pull request as draft August 23, 2023 16:29
@supertom01
Copy link
Member Author

This PR will first have to be cleaned up as @emielsteerneman and @skaeringur97 suggest.

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

Successfully merging this pull request may close these issues.

3 participants