Skip to content

BASE CONTROL, Configure ESC , IMU and Tuning PID controller for the base. ODOM Check

lawrence edited this page Sep 29, 2019 · 2 revisions

Free inspired and copied contents from: https://github.com/linorobot/linorobot/wiki/2.-Base-Controller

Calibrate ESC

Using a test app it is possible to connect directly the ESC and set the PWM. In pluto_ws/src/plutobot/teensy/firmware/lib/encoder/ESC_And_Encoder_Test run

> ESC_And_Encoder.ino

Usually you want to run on your pc the ArduinoIDE.

The ESCs and motors used are: [https://hobbyking.com/en_us/trackstar-genii-120a-1-10th-scale-sensored-brushless-car-esc-roar-brca-approved.html](TrackStar GenII 120A 1/10th Scale Sensored Brushless Car ESC (ROAR/BRCA approved))

Note the 25.5T windings per coil

[https://hobbyking.com/en_us/trackstar-1-10th-brushless-sensored-motor-v2-25-5t-for-f1.html?___store=en_us](Trackstar 1/10th Brushless Sensored Motor V2 25.5T for F1 )

ESC Programmer

Software used for control is TU USB Link V2.06

Here you can find the latest configuration for the programmer https://github.com/lawrence-iviani/Plutobot_docs/blob/master/ESC%20config/Basic_with_breaking.esc

Controller

The operation to perform are set the motor with Forward PWM, neutral Backward PWM with ESC_And_Encoder.ino This can be set via proper command in the terminal via send (rember to set the correct BAUD rate (57600) and the terminal: Both BL & CR

Connect the ESC, battery and signal line, and then press the switch button for about 3 seconds, the blue LED long bright solid, the ESC is into the transmitter calibration mode:

1. Pull the transmitter stick to maximum forward position, blue LED flash, and then the red LED lights solid.

Terminal: PWM 400

2. Then push throttle stick to max brake position, the red LED will be flashing, and then the blue and red LED lights.

Terminal: PWM -400

3. Return throttle stick to neutral position, the red and blue LED flash, and then the long light for about 2 seconds, the red and blue LED light flashing two times, return the work mode. The transmitter calibration completed.

Terminal: STOP

IMU

Before anything else, you would want to connect the IMU to the Teensy board for calibration. Since the calibration process requires you to tilt the IMU in different directions, it would be handy especially for heavier robots to calibrate the IMU before connecting the rest of the components. Connect the IMU to the Teensy board as shown below and remember to mark which side of the IMU will be facing the front. This is to ensure that the IMU's orientation is correct once you mount it in the robot. To calibrate, run the following on the robot computer:

orientation in general also if you have changed your design in a mecanum drive robot take note of the roller’s orientation below:

base direction

Open a new terminal and run minimal.launch:

roslaunch plutobot minimal.launch

On another terminal, run the IMU calibration node:

> roscd plutobot/param/imu

> mv imu_calib.yaml imu_calib0.yaml

> rosrun imu_calib do_calib

Follow the instructions on the terminal until the calibration process is done. It's normal that each step would take some time so don't terminate the program. Once done, verify if the calibration file has been saved.

ls imu_calib.yaml

Driving the robot

Now check if the wheels’ direction is correct. Lift the robot off the ground so the wheels can move freely.

On your robot's computer, run the launch file to start ROS and rosserial_python:

> roslaunch plutobot minimal.launch

On your development computer, run teleop_twist_keyboard:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py

Follow the instructions on the terminal to move the robot.

Please note the actual IMU sensor is mounted with 90 deg of rotation, the transformation is applied directly in the code

base direction

Check the encoder readings

Next, check if the encoder readings are correct from the terminal where you ran minimal.launch. All encoder readings must increase as you drive forward, and decrease as you drive in reverse.

base direction

to activate, enable the debug level, on the target bot

rosservice call /rosserial_lino/set_logger_level "{logger: rosout, level: debug}"

NOTE, this won't work if the flag DEBUG is not enabled see firmware.ino

PID Tuning

In order to maintain the speed sent by navigation stack, your PID controller has to be tuned properly. You can use lino_pid to tune your PID constants.

On your robot’s computer, open a new terminal:

Run minimal.launch:

roslaunch plutobot minimal_with_PID.launch

On your development computer, every command in a new terminal:

Run teleop_twist_keyboard:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py

Alternative way

on your development computer run pid_configure:

> rosrun lino_pid pid_configure

To visualize the on your development computer Open rqt:

rqt

Once the dashboard is open, import the .perspective file by clicking Perspective > Import and choose lino_pid.perspective from lino_pid package: ~/catkin_ws/src/lino_pid/lino_pid.perspective.

PID Graph

Click pid_configure under Dynamic Reconfigure window and slide the parameters at the bottom right window to tune your PID constants. Drive the robot and see the results from the graph.

Here are some tips how to configure your PID constants (Page 13).

Once your PID constants are tuned, record the values and edit the config file:

roscd plutobot/teensy/firmware/lib/config

nano lino_base_config.h

and change the values of K_P, K_I, K_D to the PID values you have recorded. Also, remember to change back variable DEBUG to 0.

#define K_P 0.6 // P constant

#define K_I 0.3 // I constant

#define K_D 0.5 // D constant

Upload the updated PID constants to the Teensy board:

roscd plutobot/teensy/firmware

platformio run --target upload

ODOM

Odometry message, sensor fusion see Linobot Odometry

Once everything is set, you should be able to move 1mt and 360 deg

RPM Encoder

Wrong positioning rpm reading? Check connection and counting