We propose an adaptive trajectory tracking controller for quadruped robots, which involves two prioritized layers of adaptation for avoiding possible slippage of one or multiple legs.
This package is developed for the simulated and the real robot experiments of the submitted paper to Humanoids 2023 with title "Two-layer adaptive trajectory tracking controller for quadruped robots on slippery terrains" .
Development and Implementation using Unitree's Go1 EDU legged robot, real and simulated.
Slippage detection is achieved by ProbabilisticContactEstimation.
- unitree_ros_to_real ( Packages Version: v3.5.0 )
- unitree_ros
- unitree_legged_sdk ( Packages Version: v3.5.1 )
- Ubuntu 20.04
- ROS Noetic (tested), ROS Melodic (possibly, not-tested)
-
Get the above package dependencies:
unitree_ros_to_real,unitree_ros,unitree_legged_sdk. -
Clone the repo
$ git clone https://github.com/despargy/maestro
-
Catkin make
$ cd ~/catkin_ws $ catkin_make
-
Set the "<path-to-workspace>" to your workspace path at:
- line 15, src/contact_estimation/contacts/fl_pce.py
- line 15, src/contact_estimation/contacts/fr_pce.py
- line 15, src/contact_estimation/contacts/rl_pce.py
- line 15, src/contact_estimation/contacts/rr_pce.py
| ❗ This is very important |
|---|
Warning
- Before run experiments with the real robot Go1, first secure Unitree's Go1 EDU, ex. photo below. - Default launch for simulation
$ roslaunch maestro basic.launch
- Run the controller.
$ rosrun maestro main_handler
- Terminate the controller.
$ rostopic pub /maestro/ctrl std_msgs/Bool "data: false"
- Launch for simulation with adaptation parameters.
$ roslaunch maestro basic.launch slip_detection:=true adapt_b:=true
- Launch Probabilistic Contact Estimation.
$ roslaunch maestro contact.launch
- Run the controller.
$ rosrun maestro main_handler
- Terminate the controller.
$ rostopic pub /maestro/ctrl std_msgs/Bool "data: false"
- Default launch for simulation.
$ roslaunch maestro basic.launch real_experiment:=true
- Run the controller.
$ rosrun maestro main_handler
- Terminate the controller.
$ rostopic pub /maestro/ctrl std_msgs/Bool "data: false"
- Launch for simulation with adaptation parameters.
$ roslaunch maestro basic.launch real_experiment:=true slip_detection:=true adapt_b:=true
- Launch Probabilistic Contact Estimation **.
$ roslaunch maestro contact.launch
- Run the controller.
$ rosrun maestro main_handler
- Terminate the controller.
$ rostopic pub /maestro/ctrl std_msgs/Bool "data: false"
- Default launch for simulation
$ roslaunch maestro basic.launch inf:=true
- Run the controller.
$ rosrun maestro main_handler
- Terminate the controller.
$ rostopic pub /maestro/ctrl std_msgs/Bool "data: false"
- Launch for simulation with swing adaptation parameters.
$ roslaunch maestro basic.launch slip_detection:=true adapt_b:=true inf:=true
- Launch Probabilistic Contact Estimation.
$ roslaunch maestro contact.launch
- Run the controller.
$ rosrun maestro main_handler
- Terminate the controller.
$ rostopic pub /maestro/ctrl std_msgs/Bool "data: false"
- ### Secure the real robot before the experiment.Note *: The robot's model state (CoM position) is needed since the provided controller is a closed-loop. Set the appropriate topic at line 39 of file /maestro/include/CommunicationHandler.h. Note *: In order to tune the Real Robot, it is recommended to comment 49-52 lines and comment 43-46 lines, from /maestro/launch/basic.launch, for tuning the real robot. Note *: For Real Robot first follow the steps setting the connection with Real Robot(ip: 192.168.123.161). Instruction at /maestro/go1_description/connection/Go1Config.txt
Note **: ProbabilisticContactEstimation for real experiment needs a 6DOF IMU sensor to publish at /imu topic.
Make kill_ros.sh executable, once:
chmod +x kill_ros.sh
Run kill_ros.sh, everytime to terminate ROS processes from background.
./kill_ros.sh
| Parameter name | Default Value | Description |
|---|---|---|
real_experiment |
false |
false: robot in Gazebo simulator, true: real robot connection |
slip_detection |
false |
Slip terrain perception disabled, if true: use ProbabilisticContactEstimation |
adapt_b |
false |
Adaptation disabled, if true slip_detection should be true. |
inf |
false |
Swinging leg's weights to infinity. |
num_imus |
0 |
Optional parameter waiting for msg from a specific num of IMUs, before start tracking. Slip detection needs also to be true |
world_name |
wname |
Affects only simulation world. wname: 1 leg slippage, wnameGlobal: 4 legs slippage (global slip) Select line-22 or line-24 from 'basic.launch' |
kp |
3000.0 |
Position gain of controller (tuning parameters) |
kv |
550.0 |
Velocity gain of controller (tuning parameters) |
ko |
15.0 |
Orientation gain of controller (tuning parameters) |
alpha |
150.0 |
Increasing, sharper-quiqer adaptation / Decreasing, smoother-slower adaptation (tuning parameters) |
Control of two-layer adaptation uses slip probabilbity from ProbabilisticContactEstimation package. At least one IMU sensor is required, attached to robot's leg in order to detect the slipage at this foot tip.
Set your desired trajectory and avoid slipage! Desired position trajectory is given from get_pDesiredTrajectory() at maestro/src/Math.cpp file. Desired orientation trajectory is given from get_RDesiredRotationMatrix() c.
Note Tuning of controller's gains (launch parameters) is possibly needed, after trajectory has been modified.
Note Tuning of adaptation can be achived for different robot's behavior, by changing the values of
w0line 36, /maestro/src/Leg.cpp file.alpha/maestro/launch/basic.launch file.
Despina-Ekaterini Argiropoulos - despinar@ics.forth.gr