OCS2 is a huge monorepo; DO NOT try to compile the whole repo. You only need to compile ocs2_legged_robot_ros
and
its dependencies following the step below.
-
You are supposed to clone the OCS2, pinocchio, and hpp-fcl as described in the documentation of OCS2.
# Clone OCS2 git clone https://github.com/leggedrobotics/ocs2.git # Clone pinocchio git clone --recurse-submodules https://github.com/leggedrobotics/pinocchio.git # Clone hpp-fcl git clone --recurse-submodules https://github.com/leggedrobotics/hpp-fcl.git # Clone ocs2_robotic_assets git clone https://github.com/leggedrobotics/ocs2_robotic_assets.git # Install dependencies sudo apt install liburdfdom-dev liboctomap-dev libassimp-dev
-
Compile the
ocs2_legged_robot_ros
package with catkin tools instead ofcatkin_make
. It will take you about ten minutes.catkin config -DCMAKE_BUILD_TYPE=RelWithDebInfo #important catkin build ocs2_legged_robot_ros ocs2_self_collision_visualization
Ensure you can command the ANYmal as shown in the document and below.
For the latest version of mujoco, it is very easy to install it on python:
pip3 install mujoco
pip3 install pynput #for teleop.py
pip3 install scipy
catkin config -DCMAKE_BUILD_TYPE=RelWithDebInfo #important
catkin build humanoid_controllers humanoid_legged_description mujoco_sim
# To start simulation with the cheat state estimator.
# Press SPACE on mujoco simulation window and input the gait command.
roslaunch humanoid_controllers load_cheat_controller.launch
# To start simulation with the normal state estimator.
roslaunch humanoid_controllers load_normal_controller.launch
# To start only the NMPC module and simulate with OCS2 dummy node
roslaunch humanoid_dummy legged_robot_sqp.launch
The effect of the simulation is shown in the video provided in this link. (Note: The video version is older, and the actual effect may vary depending on the latest code).
The foot planner is a switch model provided by OCS2, which switch the contact status between right foot and left foot. The foot planner only plans the z-axis of swinging foot as Cubic Spline.
The state estimator only needs to estimate the coordinates and linear velocity of the trunk. It is a linear Kalman filter, where the system's state equation is
where
Where the subscript
In the state estimator,
The NMPC part solves the following optimization problems at each cycle through the formulation and solving interfaces provided by OCS2:
In this framework, the system state
where
- Friction cone;
- No motion at the standing foot;
- Zero force at the swinging foot;
- The z-axis position of the swinging foot satisfies the gait-generated curve;
- No motion for the roll axis of the foot.
To solve this optimal control problem, a multiple shooting is formulated to transcribe the optimal control problem to a nonlinear program (NLP) problem, and the NLP problem is solved using Sequential Quadratic Programming (SQP). The QP subproblem is solved using HPIPM.
WBC only considers the current moment. The WBC optimization task is expressed in the following form according to qpOASES:
Where
where
In weighted WBC, a portion of the tasks serves as weighted costs, providing the optimization problem's
Type | Task |
---|---|
cost | Base XY linear acceleration task |
cost | Base Z position task (using PD controller to estimate the acceleration) |
cost | Base Angular task (using PD controller to estimate the acceleration) |
cost | Swing leg position task (using PD controller to estimate the acceleration) |
cost | Contact force task |
constraint | Floating base EOM task |
constraint | Torque limit task |
constraint | Friction cone task |
Every task is defined as a quadruple
To formulate the QP problem from task definitions, we use the following formula:
For cost task, we have
For equality constrained task, we have
For non-equality constrained task, we have
The stacking of tasks is defined as the concatenation of the matrices
Obtain optimized joint positions and joint velocities from MRT (Model Reference Tracking), obtain joint accelerations and joint torques from WBC (Whole Body Control), and feed them into a PD controller after processing. MRT, based on the trajectory optimized by NMPC, obtains the optimized states and inputs at a high frequency.
where
Module | Frequency |
---|---|
NMPC | 100Hz |
MRT | 500Hz |
WBC | 500Hz |
PD Controller | >1000Hz |
State Estimate | 500Hz |
To ensure the speed of the program, it is crucial that you optimize the code at least to the RelWithDebInfo level. This is highly important!
legged-control by Qiayuan Liao: Nonlinear MPC and WBC framework for legged robot based on OCS2 and ros-controls.
hunter-bipedal-control by BridgeDP: An open source bipedal robot control framework, based on non-linear MPC and WBC, tailered for EC-hunter80-v01 bipedal robot.
pai-sim by High-Torque: Acknowledgement for the Mujoco simulation framework in python.