Python library for humanoid robotics based on OpenRAVE:
- Whole-body inverse kinematics (IK) based on the weight-prioritized multi-task framework
- Contact-stability areas and volumes: multi-contact ZMP support areas, CoM acceleration cones, etc.
- Linear Model Predictive Control (MPC) and state machines for locomotion
- Jacobians and Hessians for center of mass (CoM) and angular momentum
- Types and algorithms to manipulate polytopes and polyhedral cones
- Interface to linear programming (LP) and quadratic programming (QP) solvers
- Dynamic walking over rough terrains based on nonlinear model predictive control of the floating-base inverted pendulum model
- Multi-contact walking pattern generation based on linear model predictive control of 3D CoM accelerations
- Multi-contact ZMP support areas for locomotion in multi-contact scenarios (including hand contacts)
- Humanoid stair climbing demonstrated on a Kawada HRP-4 robot
First, you will need to install OpenRAVE. Here are some instructions for Ubuntu 14.04 and Ubuntu 16.04.
Next, install all Python dependencies with:
sudo apt-get install cython libglpk-dev python python-dev python-pip python-scipy python-simplejson
sudo pip install quadprog pycddlib
sudo CVXOPT_BUILD_GLPK=1 pip install cvxopt
Finally, clone the repository, and run the setup script:
git clone https://github.com/stephane-caron/pymanoid.git && cd pymanoid
python setup.py build
python setup.py install --user
For nonlinear optimal control, you will need to install CasADi, preferably from source to install the MA27 linear solver as well.
Some minor functions to manipulate polygons may also require two small
libraries: sudo pip install pyclipper
.
Q: Do you implement dynamics simulation in Pymanoid? If yes, could you give me some pointers? If no, how do you verify the stability of the robot?
Forward dynamics need a reaction-force model, which is a tricky thing to do in rigid body dynamics. This stems from an essential "contradiction" of the model: physically, reaction forces depend on local deformations between bodies in contact, while the main assumption of rigid body dynamics is that bodies are not deformable. To overcome this, two main approaches have been explored: regularized reaction-force models (a.k.a. "jedi" physics) and non-smooth approaches. Both have pros and cons in terms of realism and numerical integration. For more details, check out the Wikipedia page on contact dynamics.
Pymanoid does not provide forward dynamics. The stability that is checked in
simulations is a feasibility criterion called contact
stability, namely, that
at each timestep there exists feasible contact forces that support the robot
motion. This check is performed by the find_supporting_wrenches()
function of a ContactSet.
Q: How can I record a video of my simulation?
For a quick and dirty solution, you can record your whole desktop using e.g.
kazam. However, with this approach the video
time will be your system time, potentially slowed down by all other processes
running on your machine (including kazam
itself).
To record a video synchronized with your simulation time, call
sim.record("filename.mp4")
. This will schedule an extra CameraRecorder
process that takes a capture of your simulation window after each step. You can
then run your simulation as usual. Once your simulation is over, call the
make_pymanoid_video.sh
script created in the current folder. It will
reassemble screenshots into a properly timed video filename.mp4
.
Q: the video script returns an error "width/height not divisible by 2".
Bad choice of window size ;) You will need to crop the PNG files in the
pymanoid_rec/
temporary folder. For instance, if the resolution of these
files is 1918x1059, cd
to that folder and run mogrify -crop 1918x1058+0+0 *.png
.