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

PID Controller #35

Open
PaddyCube opened this issue Jul 13, 2021 · 6 comments
Open

PID Controller #35

PaddyCube opened this issue Jul 13, 2021 · 6 comments

Comments

@PaddyCube
Copy link

Hello,
could you please explain the values of PID controller? What is f, antiwindup, i_clampmin and i_clampmax good for?
I tried different values with no luck so far. Acceleration seems to work but when I stop the robot with a velocity of 0m/s, it starts to oscillate back and forth endless

@fjp
Copy link
Member

fjp commented Jul 13, 2021

Hi @PaddyCube

anti-windup is to preventing the integral error from growing too much. Put in a simple python example this is how the integral error is clamped (in this example between -2 and 2):

e_int = max(min(e_int,2),-2)

F is the feedforward term and used to reach the set point faster.

Which hardware and "version" of diffbot are you using? The reason I am asking is because there are basically two approaches, where to put the PID controller:

  1. Having the PID controller in the high level hardware interface - found in 0.0.2.
  2. Running the PID controller on the low level firmware source code - implemented in noetic-devel, which is implemented on tag 1.0.0 .

Recently, I made a major code change regarding where to put the PID controller. Option 2 is currently my preferred method and implemented in the latest commits of noetic-devel, because the behaviour seems to be more stable. Using option 2 also means that the dynamic reconfigure parameters (F, P, I, D and anti-windup feature) in the high level hardware interface are not used anymore. I didn't remove the code however, to allow/show both methods, but this might change in the future.

With option 1 you have the comfort of dynamic reconfigure to tune the (F)PID controller but for me definetely the second option feels more stable. To tune the PID values with the second option you need to change the values in code. I am planning to use dynamic reconfigure however, and send topics to the low level firmware running on the Teensy mcu.

In general I cannot recommend which option to choose but for me definitely option 2 worked better so far.

To tune the PID controller, this youtube video might help. It gives some insights what the PID parameters influence. Regarding the F term, I would start setting it to zero.

@fjp fjp closed this as completed Aug 10, 2021
@darld
Copy link

darld commented Sep 1, 2021

Is possible to disable the PID, so the robot wouldn't oscillate during the teleops?

@fjp
Copy link
Member

fjp commented Sep 1, 2021

@darld disabling the PID is not directly possible, since you would create an open loop without feedback from the velocity error. Therefore, I would first suggest to tune the PID correctly to avoid the oscillations. This way you can leverage all the features from ROS Controls diff_drive_controller.

However, in case you don't want to use this controller, you could also try to update the write() method of the base_controller that is running on the low level microcontroller:

// Compute PID output
// The value sent to the motor driver is calculated by the PID based on the error between commanded angular velocity vs measured angular velocity
// The calculated PID ouput value is capped at -/+ MAX_RPM to prevent the PID from having too much error
motor_cmd_left_ = motor_pid_left_.compute(wheel_cmd_velocity_left_, joint_state_left_.angular_velocity_);
motor_cmd_right_ = motor_pid_right_.compute(wheel_cmd_velocity_right_, joint_state_right_.angular_velocity_);
p_motor_controller_left_->setSpeed(motor_cmd_left_);
p_motor_controller_right_->setSpeed(motor_cmd_right_);
}

This is where the PID is used to compute the PWM motor signals from the velocity error. Instead of calling the PID you would have to translate the commanded velocity (from the diff_drive_controller) to a PWM signal, for example using a simple mapping. Then you also have to make sure that the commanded velocities from the diff_drive_controller are actually applied on the motors. Otherwise the error can grow and you produce an open loop.

@darld
Copy link

darld commented Sep 2, 2021

Not sure whether I can just set the error_ = 0, therefore no error compute in the open loop.

double PID::operator()(const double &measured_value, const double &setpoint, const ros::Duration &dt)
{
// Compute error terms
error_ = setpoint - measured_value;
ROS_DEBUG_STREAM_THROTTLE(1, "Error: " << error_);

@fjp
Copy link
Member

fjp commented Sep 2, 2021

Please note that this is the "old" PID controller that was running in the high level hardware interface, as I mentioned in my comment previously. If you flashed the script/base_controller on your microcontroller, tuning these PID parameters with dynamic reconfigure or even setting the error_ = 0 won't have any effect. If you want to work with the high level PID you should flash the source code found in the scripts/encoders folder:

image

However, I would suggest you try to use the base_controller firmware. The PID values which you then have to tune are found in the diffbot_base_config.h here:

#define K_P 0.6 // P constant
#define K_I 0.3 // I constant
#define K_D 0.5 // D constant

The drawback of this method is that you currently have to re-flash the microcontroller every time you change the PID values. However, I am planning to add a topic to change these values for a better tuning experience.

@fjp
Copy link
Member

fjp commented Sep 2, 2021

Regarding the tuning process. You mentioned oscillations, which might happen because of a too high proportional gain. So I would start the tuning by setting these values:

P = something small until no oscillations are observable
I = 0
D = 0

Only increase the I and D gains once you see stable results with a P value not equal to zero.

Setting the error_ = 0 is definitely not what you want, because then the commuted output command from the PID will be always zero (u(t) = 0 in the formula below).

image

@fjp fjp reopened this Sep 2, 2021
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

No branches or pull requests

3 participants