The walking-controllers project is a suite of modules for achieving bipedal locomotion on humanoid robots such as iCub or ergoCub.
The suite includes:
- Walking_module: this is the main module and it implements all the controller architecture that allows the robot to walk.
- Joypad_module: this module allows using the Joypad as reference input for the trajectory generated by the Walking Module
- WalkingLogger_module: an module that can be useful to dump data coming from the Walking Module
- walking-controllers
- Overview
- π Some theory behind the code
- π Dependencies
- π¨ Build the suite
- π» How to run the simulation - Additional Dependencies - How to run
- π How to test on the robot
This module allows humanoid robots walking using the position control interface. It implements the following architecture where two controller loops can be distinguished:
- an inner ZMP-CoM control loop http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=4359259&tag=1;
- an outer DCM control loop:
- model predictive controller;
- reactive controller.
Two different inverse kinematics solver are implemented:
- a standard non-linear IK solver;
- a standard QP Jacobian based IK solver.
A paper describing some of the algorithms implemented in this repository can be downloaded here. If you're going to use the code developed for your work, please quote it within any resulting publication:
G. Romualdi, S. Dafarra, Y. Hu, D. Pucci "A Benchmarking of DCM Based
Architectures for Position and Velocity Controlled Walking of Humanoid Robots",
2018
The bibtex code for including this citation is provided:
@misc{1809.02167,
Author = {Giulio Romualdi and Stefano Dafarra and Yue Hu and Daniele Pucci},
Title = {A Benchmarking of DCM Based Architectures for Position and Velocity Controlled Walking of Humanoid Robots},
Year = {2018},
Eprint = {arXiv:1809.02167},
}
- YARP: to handle the comunication with the robot;
- iDynTree: to handle the robot kinematics;
- iCubContrib: to configure the modules;
- icub-main: to smooth and integrate signals;
- osqp-eigen: to solve the MPC problem;
- qpOASES: to solve the IK problem;
- Unicycle footstep planner: to generate a trajectory for the DCM;
- bipedal-locomotion-framework: for locomotion functionalities;
- Gazebo: for the simulation (tested Gazebo 8, 9 and 10);
- Catch2: to compile the tests.
git clone https://github.com/robotology/walking-controllers.git
cd walking-controllers
mkdir build && cd build
cmake ../
make
[sudo] make install
Notice: sudo
is not necessary if you specify the CMAKE_INSTALL_PREFIX
. In this case it is necessary to add in the .bashrc
or .bash_profile
the following lines:
export WalkingControllers_INSTALL_DIR=/path/where/you/installed/
export PATH=$PATH:$WalkingControllers_INSTALL_DIR/bin
export YARP_DATA_DIRS=$YARP_DATA_DIRS:$WalkingControllers_INSTALL_DIR/share/ICUBcontrib
In order to run the simulation, the following additional dependency are required:
-
Set the
YARP_ROBOT_NAME
environment variable according to the chosen Gazebo model for instance for the modelergoCubGazeboV1
:export YARP_ROBOT_NAME="ergoCubGazeboV1"
-
Run
yarpserver
yarpserver --write
-
Run gazebo and drag and drop robot model (e.g.
ergoCubGazeboV1
):export YARP_CLOCK=/clock gazebo -slibgazebo_yarp_clock.so
-
Run
whole-body-dynamics
, for instance for the modelergoCubGazeboV1
:yarprobotinterface --config conf/launch_wholebodydynamics_ecub.xml
-
Run the walking module
YARP_CLOCK=/clock WalkingModule
-
communicate with the
WalkingModule
:yarp rpc /walking-coordinator/rpc
the following commands are allowed:
prepareRobot
: put ergoCub in the home position;startWalking
: run the controller;pauseWalking
: the controller is paused, you can start again the controller sendingstartWalking
command;stopWalking
: the controller is stopped, in order to start again the controller you have to prepare again the robot.setGoal (x, y, k)
: send the desired input to the planner. Send this command afterstartWalking
.
Example sequence:
prepareRobot startWalking setGoal (1.0, 0.0, 0.0) setGoal (1.0, 0.0, 0.0) stopWalking
The Joypad application, called WalkingJoypadModule
, allows you to send all the rpc commands using the buttons. The application processes the button press events associating them to the pre-defined rpc commands which are then sent through Yarp to the Walking Coordinator module. The joypad keys mapping is as follows:
A
for preparing the robotB
for start walkingY
for pause walkingX
for stop walking
Suppose that you want to run the Joypad application, called WalkingJoypadModule
in the same machine where the physical device is connected. The only thing that you have to do is running the following command from the terminal:
YARP_CLOCK=/clock WalkingJoypadModule
The application will take care to open an SDLJoypad
device.
While, if you want to run the WalkingJoypadModule
in a machine that is different form the one where the physical devce is connected. The
JoypadControlServer
-
JoypadControlClient
architecture is required. In details:
-
Run the
JoypadControlServer
device in the computer where the joypad is physically connected:YARP_CLOCK=/clock yarpdev --device JoypadControlServer --use_separate_ports 1 --period 10 --name /joypadDevice/xbox --subdevice SDLJoypad --sticks 0
-
Run the
WalkingJoypadModule
in the other computerYARP_CLOCK=/clock WalkingJoypadModule --device JoypadControlClient --local /joypadInput --remote /joypadDevice/xbox
In order to enable the sideways walking it is necessary to set the parameter controlType
to direct
in the plannerParams
configuration file. In this configuration, the goal set with setGoal
is interpreted as a desired velocity reference for the unicycle. In this case, setGoal
expects three doubles that represent the forward velocity, angular velocity, and lateral velocity. For example
setGoal (0.0 0.0 1.0)
will command the robot to step sideways to the left.
In case the planner fails in finding a solution, it is possible to reduce the values in saturationFactors
in the plannerParams
file. These numbers represent conservative factors that multiply the unicycle velocity saturations computed from the other parameters, like the minStepDuration
. The first number multiplies the saturation for the linear and lateral velocity. The second number multiplies the angular velocity saturation. Suggested values for saturationFactors
:
personFollowing
case:(0.9, 0.7)
direct
case:(0.7, 0.7)
β
The WalkingModule
opens a port named by default /walking-coordinator/goal:i
(it can be edited from the main configuration file). This port expects a vector of double of size 2 if the controlType
in plannerParams
is set to personFollowing
, or 3 if the value is direct
. In the first case, they represent the x and y position in a robot centered frame of the desired point to reach. In the second case, they represent the desired unicycle velocities.
The range of the numbers is expected to be [-1, +1]
. Some scaling can be applied in the main configuration file through the parameter goal_port_scaling
. Suggested scaling:
personFollowing
case:(10.0, 10.0, 1.0)
(the third input is not considered)direct
case:(0.5, 1.0, 0.5)
Before running WalkingModule
check if dump_data
is set to 1. This parameter is set in a configuration ini
file depending on the control mode, for instance controlling from the joypad: src/WalkingModule/app/robots/${YARP_ROBOT_NAME}/dcm_walking_with_joypad.ini
. Example for the model ergoCubGazeboV1
Then you can log your data with YarpRobotLoggerDevice
.
You can change the DCM controller and the inverse kinematics solver by editing these parameters.
The Inverse Kinematics block configuration can be set through the file src/WalkingModule/app/robots/ergoCubGazeboV1/dcm_walking/joint_retargeting/inverseKinematics.ini
.
The Inverse Kinematics block uses an open source package for large-scale optimisation, IPOPT (Interior Point Optimizer), which requires other packages like BLAS (Basic Linear Algebra Sub-routines), LAPACK (Linear Algebra PACKage) and a sparse symmetric indefinite linear solver (MAxx, HSLMAxx, MUMPS, PARDISO etc). Further documentation can be found at https://coin-or.github.io/Ipopt and https://coin-or.github.io/Ipopt/INSTALL.html#EXTERNALCODE. The package IPOPT installed with the superbuild (via homebrew or conda) is built with the solver MUMPS by default, which is reflected in the default configuration of the Inverse Kinematics block src/WalkingModule/app/robots/ergoCubGazeboV1/dcm_walking/joypad_control/inverseKinematics.ini#L14-L17:
# solver paramenters
solver-verbosity 0
solver_name mumps
max-cpu-time 20
For instance, for using MA27 solver instead of MUMPS, replace mumps
by ma27
.
In case you encounter issues when starting the Walking Module with the selected options, you can increase the verbosity to 1 for additional debug information.
You can follows the same instructions of the simulation section without using YARP_CLOCK=/clock
. Make sure your YARP_ROBOT_NAME
is coherent with the name of the robot (e.g. ergoCubSN000
)
Currently the supported robots are only:
iCubGazeboV3
ergoCubGazeboV1
ergoCubSN000
Yet, it is possible to use these controllers provided that the robot has powerful enough legs. In this case, the user should define the robot specific configuration files (those of ergoCubSN000
are a good starting point). If you want to try these, feel free to open an issue to track your progress.
- Giulio Romualdi (@GiulioRomualdi)
- Stefano Dafarra (@S-Dafarra)