This package contains an example to demonstrate the functionality of the CUDA-based GRiD (GPU-Accelerated Rigid Body Dynamics) library. The repository can be used to verify that GRiD Python is set up and running correctly on your machine.
GRiD is a library of functions that computes physics quantities needed for trajectory planning algorithms by generating CUDA kernels for your specific robot.
Example GRiD Usage: Trajectory Planning
- A target pose is defined using joint angles or end-effector positions and converted into a series of waypoints from the current pose.
- A motor control algorithm is used to calculate the torques needed to move the robot to the next waypoint.
- GRiD is invoked and
forward_dynamicsis called to convert the calculated torques into accelerations - An integrator is used to convert the accelerations into updated velocities and positions.
- The robot moves to the next waypoint, and steps 2-4 is repeated until the final target position is reached.
An example of this use case can be found in the implementation of KKT systems solvers in MPCGPU.
This package contains several layers of submodules! Make sure to run git submodule update --init --recursive after cloning.
Note: GRiD's dependencies are not be automatically installed. Make sure to follow the submodule's README to install any additional dependencies for GRiD.
pip install GRiD/bindings
To use the GRiD Python in your project, include from GRiD.bindings import gridCuda at the top of your file.
To test the installation of the GRiD bindings, run:
python hello_grid.py
hello_grid.py is a minimal but complete "hello world" program using GRiD's Python Bindings. The goal of the demo is to verify that both forward dynamics and inverse dynamics are working correctly and to illustrate how GRiD fits into a typical robot control loop.
The demo simulates the motion of the front-left HFE (hip flexion/extension) joint of the HyQ quadruped robot (see pages 83-85). Specifically, it:
- Defines a target joint angle for the HFE joint.
- Uses a simple PD controller to compute required joint accelerations.
- Uses inverse dynamics to compute the motor torque required to achieve that acceleration, accounting for gravity and other biases.
- Uses forward dynamics to simulate how the robot responds to that torque.
- Integrates joint accelerations over time to update joint velocities and positions.
- Plots joint motion and other control values for visualization.
These steps are repeated in a loop to move the joint to the desired angle and hold it there for a specified number of simulation time steps. This approach is commonly referred to as computed-torque control.
Several graphs are saved as PNG files in the plots folder as part of the demo.
This plot shows the actual HFE joint angle as the controller moves it toward the target.
- The horizontal axis is time (seconds)
- The vertical axis is joint angle (radians)
- A dashed line indicates the target angle
This plot helps check if the joint reach the desired position smoothly and accurately.
This plot shows the motor torque applied at the HFE joint.
- The horizontal axis is time (seconds)
- The vertical axis is torque (Nm)
This plot illustrates:
- How much effort the motor applies to move the joint
- The large initial torque needed to accelerate the leg
- The steady torque required to hold the joint against gravity once it reaches the target
This plot compares:
- The desired/ideal joint acceleration computed by the PD controller
- The actual joint acceleration produced by GRiD's calculated dynamics
This plot demonstrates:
- How closely the robot follows the commanded acceleration
- The effect of inertia, gravity, and coupling on the system response
- Good overlap between the curves indicates inverse and forward dynamics are consistent
Full API Reference and Documentation
GRiDDataFloat(q, qd, u): Single-precision (float) implementation of RBD functions- Note that the double implementation caused errors
load_joint_info(q, qd, u): Update the input parameters for RBD calculationsget_end_effector_positions(): Calculates end-effector posesget_end_effector_position_gradients(): Calculates end-effector pose gradientsinverse_dynamics(): Calculates the RNEA torque vectorminv(): Calculates the inverse of the mass matrixforward_dynamics(): Calculates joint accelerationsinverse_dynamics_gradient(): Calculates Jacobian of inverse dynamics w.r.t q and qdforward_dynamics_gradient(): Calculates Jacobian of forward dynamics w.r.t q and qd
NUM_JOINTS: Number of joints defined in the URDFNUM_EES: Number of end-effectors based on the URDF specification
C++11 compatible compiler
CUDA Toolkit >= 11.1 (compatible with compute capability 8.6)
CMake >= 3.10
Python >= 3.6
pybind11