This folder contains the gait optimization implementation for Talos, that is used for comparison between RAPTOR and aligator.
Our main function is mainly at TalosSingleStepFixedPosition.cpp, where we try to solve for a trajectory that makes Talos walk forward with a user-specified step length while starting from a fixed initial configuration.
Create a data/ folder first in Examples/Talos to store all the results.
Specify the step length in singlestep_optimization_settings.yaml and run the following command in build/:
./Talos_exampleThis program runs the optimization and then save the trajectories and the corresponding inverse dynamics control inputs in data/solution-talos-forward-[step length].txt, over a much finer time discretization.
Check line 196-210 in TalosSingleStepFixedPosition.cpp.
In Examples/Talos/python/talos_simulation.py, you will be able to find how we simulate the Talos using scipy.solve_ivp as the integrator and pinocchio to evaluate the contact dynamics.
Here we apply a tracking controller in the simulation:
Here, data/solution-talos-forward-[step length].txt using zero-order hold (ZOH).
We also added a simple PD control here where the desired trajectories are also recovered from data/solution-talos-forward-[step length].txt using ZOH.
For our implementation on the comparisons using aligator, please refer to our fork on aligator.
This folder provides a framework for optimizing gaits for different humanoid robots. To migrate the code, you can copy this folder and replace all instances of Talos with the name of your robot.
Below are the key modifications required for migration:
-
URDF File Paths
Updateurdf_filenamein the main files such asTalosSingleStep.cppandTalosMultipleStep.cpp.
You may also need to update thefilepathin the same files. -
Floating Base Representation
RAPTOR requires a URDF where the robot is attached to a floating base with:- Three prismatic joints (for translation)
- Three revolute joints (for rotation)
You need to manually create this modified URDF.
Refer to talos_reduced_armfixed_floatingbase.urdf as an example. -
Torso Rotation Joint Name
In line 214 ofTalosDynamicsConstraints.cpp, ensure that theRzjoint (which allows torso rotation around the world z-axis) matches the corresponding joint in your URDF.- For example, in the same location of
G1DynamicsConstraints.cpp, this joint is renamed toRz_jointto be consistent with the corresponding URDF.
- For example, in the same location of
Update the paths to the optimization configuration files in the main files:
singlestep_optimization_settings.yamlmultiplestep_optimization_settings.yaml
These paths appear in TalosSingleStep.cpp and TalosMultipleStep.cpp.
Modify the following constants in TalosConstants.h to match your robot:
-
Joint Limits & Torque Limits
These should be available from your robot's URDF. -
Ground Friction Coefficients
MU: Translational friction coefficient.GAMMA: Torsional friction coefficient.
-
Foot Joint Names
UpdateLEFT_FOOT_NAMEandRIGHT_FOOT_NAMEinTalosConstants.h.
These are typically the last joints in the kinematic chain of each leg. -
Foot Frame Transformation
The foot frame refers to the center of the bottom of the foot, which may not coincide with the foot joint.
Update the transformation matrices in:stance_foot_endTinTalosDynamicsConstraints.cppleftfoot_endTandrightfoot_endTinTalosCustomizedConstraints.cpp
Where to find this transformation matrix?
- Digit-v3: Available in its MuJoCo XML file (
digit-v3.xml). - Talos: Defined in the URDF (same as the foot link mesh frame).
- Unitree-G1: Defined in the URDF (foot frame is at the center of four corner spheres used for collision).
-
Foot Size
UpdateFOOT_WIDTHandFOOT_LENGTHinTalosConstants.h.FOOT_WIDTH= half of the size of foot along the x axis of the foot frame.FOOT_LENGTH= half of the size of foot along the y axis of the foot frame.
Note that
FOOT_WIDTHis not necessarily the short side andFOOT_LENGTHis not necessarily the long side. If the robot exhibits instability (e.g., tilting unnaturally), you may have assigned incorrect foot dimensions.
By making these modifications, you should be able to optimize gaits for your humanoid robot using this framework. One example of this migration can be found in Unitree-G1, where we duplicated the contents of this folder and modified the necessary components as outlined above.