Closed 0xraks closed 1 year ago
Hi @0xraks, these are set in the low-level base_controller
running on the teensy mcu. As you correctly notice the PID class takes these values:
The values min max values are passed in the template implementation of the BaseController constructor:
The definition is found in:
This is the same as Linorobot is doing it, see here for example.
Adjusting these hopefully helps. Would be interesting to know which values worked out for you in the end. Thanks!
Hey! Thanks for the detailed explanation. I am using stepper motors so its RPM depends on the frequency of the pulse and not pulse width. So hopefully this will work for me. I'll do some tests next weekend! Thanks a lot again!
Hey @fjp , I changed the _PWMMIN and _PWMMAX macros to -30000 and 30000 respectively. I gave it a test spin today and my motor oscillates forward and backward. It's kind of like accelerates > decelerate > change direction > and repeats . I think this has something to do with the PID tuning. Am I supposed to change any other config apart from the PWM max and PWM min to make PID happy with my new values? So far I've updated the values of _ENCODERRESOLUTION in the firmware. And also the Wheel separation, Wheel radius, in the yaml config.
I'm using stepper motors along with analogWriteFrequency (values between 0 and 30KHz) to control the speed.
Hey @0xraks,
I think this has something to do with the PID tuning
Yes, that is most likely the case
So far I've updated the values of ENCODER_RESOLUTION in the firmware. And also the Wheel separation, Wheel radius, in the yaml config.
Good, that is important to do.
Am I supposed to change any other config apart from the PWM max and PWM min to make PID happy with my new values?
The most important values for PID tuning are found here:
You should be able to change them at run time with the topics pid_left
and pid_right
but I haven't tested that feature much (introduced in db48dceee9fbb099f4571761a121d0f0c2c195ad). Alternatively, you can update them in the source diffbot_base_config.h
mentioned above and re-build and flash your firmware. Changing the PID values in source is what you should do anyway after you have found some good values.
For tuning, I would start with K_I
(Integral gain), K_D
(Differential gain) set to zero and also set K_P
(Proportional gain) to a low value at first, for example 0.1
(or even 0.01
). Then test (spin the wheels) using for example rqt_robot_steering
and observe the behaviour. If nothing happens then the K_P
gain is probably set too low and needs to be increased. If you get some oscillations, eitehr reduce K_P
or start to tune K_D
. For example increase the K_D
gain slightly but keep it below K_P
. Increasing K_D
should dampen the osciallations. After tuning these two values you can increase K_I
slightly as well.
You can find more details here in the documentation: https://ros-mobile-robots.com/packages/diffbot_base/pid/#pid-tuning. Also the top of the page (https://ros-mobile-robots.com/packages/diffbot_base/pid/) shows the process and explains more about the two PID Controllers (one for each motor). Finally, the gain trim model is explained, which might be relevant for you after sucessfully tuning your PID values.
Hope this will help you to tune everything and get a smooth behavior. If you feel there is anything unclear, please let me know. Thanks!
Hey @fjp, I tried to tune the PID, but unfortunately it didn't help. I either see oscillations or the there is a motor runaway (starts to accelerate and does respond to any commands, teensy needs to be reset to recover.)
I turned off the low level PID by commenting out the lines
motor_cmd_left_ = motor_pid_left_.compute(wheel_cmd_velocity_left_, joint_state_left_.angular_velocity_);
and
motor_cmd_right_ = motor_pid_right_.compute(wheel_cmd_velocity_right_, joint_state_right_.angular_velocity_);
.
It did the job. The motors run fine, but the response is not as smooth.
I'm trying to further understand the low level PID to get it working. I was wondering if you could help answer a couple questions that I had on this.
I see that the input and output to the PID are velocities, but the PID min_val and PID max_val are PWM duty cycle? Shouldn't the PID be applied on the PWM instead of the velocities? I'm planning to give this a shot to see if this works, let me know what you think.
Thanks!
Hey @0xraks in this case there might be other issues than tuning the PID. Let's do a step back and try to look at the hardware setup.
There might be an issue with the software regarding the stepper motors you mention you are using. For Remo and Diffbot I used the DG01D-E brushed DC motors, which include an encoder. Are you using also the Adafruit DC motor + stepper FeatherWing as your motor driver and its ? It supports two stepper motors but I am not sure if it will be setup correctly with the current implementation of Diffbot. You can see the setup for Remo here:
I assume the stepper motors provide the encoder information (ticks) via i2c. So there is probably no direct connection between the encoders (from the motors) to the expected inputs on the Teensy as it is the case for Remo.
That might explain why you get better results without the PID. In general when you use a closed-loop stepper motor the microcontroller does not need the encoder connected because it can assume that every step pulse was not missed. Simply counting how many steps sent is good enough. You also don't need a speed control PID loop if you are using a step/direction interfaced motor, as the pulse rate controls the speed exactly. Because of that you might need to make your own implementation of the MotorControllerInf and implement it according to the motor controller you have. Then you can most likely use the (angular joint) speed (calculated by the high-level diff_drive_controller
directly and set it for the stepper. Or maybe the stepper software/library you are using has another interface such as RPM? In case you have the adafruit DC motor + stepper FeatherWing everything might work already when you set the wheel_cmd_velocity_left/right_
as speed directly:
p_motor_controller_left_->setSpeed(wheel_cmd_velocity_left_);
p_motor_controller_right_->setSpeed(wheel_cmd_velocity_right_);
It would be also interesting to see your debug output. You could for example check the base_controller
debug output when the PID is on. Also do you get a specific error when there is a motor runaway?
If you don't see any debug output you can check that you have enabled it in the config file:
I turned off the low level PID by commenting out the lines motor_cmdleft = motor_pidleft.compute(wheel_cmd_velocityleft, joint_stateleft.angularvelocity); and motor_cmdright = motor_pidright.compute(wheel_cmd_velocityright, joint_stateright.angularvelocity);.
Which commands are you sending to the motor in this case when you switched the PIDs off?
I see that the input and output to the PID are velocities, but the PID min_val and PID max_val are PWM duty cycle? Shouldn't the PID be applied on the PWM instead of the velocities?
For Remo with its brushed DC motors the PID is basically where the conversion between speed and voltage (or PWM) happens. For the steppers there is most likely a different interface and it depends what inputs it expects.
Which step type is set for your steppers? I guess the behavior of steppers also depends on it.
Hey @fjp, I'm sorry I haven't gotten back to you in weeks. We used a Hybrid Servo motor (Nema34s with closed-loop drivers). We finally decided to only go with the high-level PID and disable the PID on the teensy altogether. The project went great. Thank you very much for your help!! :)
Can anyone tell me where min_val and max_val are declared ? When declaring motor_pidleft and motor_pidright, I see that we are not passing these values?
PID motor_pid_left_;
PID motor_pid_right_;
In my motor driver, I need to set the output limits to -30000 to 0 and 0 to 30000. So I'm trying to change these limits. I tried the map function, but it did not work well. Any help is appreciated. Thanks!