Installation | Quick Start | Infrastructure | Contributing
---Safe Protective and Assistive Robot Kit (SPARK) offers configurable trade-offs between safety and performance, enabling it to accommodate diverse user needs. Its modular architecture and user-friendly APIs ensure seamless integration with a wide range of tasks, hardware platforms, and customization requirements. Additionally, SPARK provides a simulation environment featuring diverse humanoid-safe control tasks, serving as benchmark baselines. By leveraging SPARK, researchers and practitioners can accelerate humanoid robotics development while maintaining strong guarantees on hardware and environmental safety.
This project also serves as the homework platform for Carnegie Mellon University's graduate course 16-883: Provably Safe Robotics, which focuses on the design and verification of safe robotic systems through planning, learning, control, and formal verification techniques.
For more information, please visit our project website. If you find this code useful, consider citing our paper:
@article{
sun2025spark,
title={SPARK: A Modular Benchmark for Humanoid Robot Safety},
author={Sun, Yifan and Chen, Rui and Yun, Kai S and Fang, Yikuan and Jung, Sebin and Li, Feihan and Li, Bowei and Zhao, Weiye and Liu, Changliu},
journal={arXiv preprint arXiv:2502.03132},
year={2025}
}
Choose one to follow depending on your OS.
With conda available but NO conda env (e.g., base) activated, run one of the following.
If no ROS-related utilities are used:
./install.sh --name <env_name>
If ROS is needed in running pipelines:
./install.sh --ros --name <env_name>
To remove installed environment:
conda remove --name <env_name> --all
Follow the same steps as the instruction above for Ubuntu 20.04. Use mjpython
instead of python
to run scripts which use Mujoco.
This step is only necessary if you plan to deploy on a real robot. Otherwise, you can skip it.
# Clone and install the unitree_sdk2_python package separately
cd ~ # Move to the home directory or any other directory outside SafeG1
git clone https://github.com/unitreerobotics/unitree_sdk2_python.git
cd unitree_sdk2_python
pip install -e .
After installation, try running a implemented safe teleoperation pipeline. A quick example is:
python example/run_g1_safe_teleop_sim.py
To run a implemented benchmark pipeline, you can run:
python example/run_g1_benchmark.py
To create a pipeline based on the benchmark configuration, you can follow the example below to test the Control Barrier Function (CBF) on a fixed-base humanoid robot. First, import necessary modules:
from spark_pipeline import G1BenchmarkPipeline as Pipeline
from spark_pipeline import G1BenchmarkPipelineConfig as PipelineConfig
from spark_pipeline import generate_g1_benchmark_test_case
Then load and customize the pipeline configuration
# Initialize the configuration
cfg = PipelineConfig()
# Load a predefined configuration for a fixed-base robot with first-order dynamics,
# targeting arm goals amidst dynamic obstacles
cfg = generate_g1_benchmark_test_case(cfg, "G1FixedBase_D1_AG_DO_v0")
# Set the safety algorithm to Control Barrier Function and configure its parameters
cfg.algo.safe_controller.safe_algo.class_name = "BasicControlBarrierFunction"
cfg.algo.safe_controller.safe_algo.lambda_cbf = 1.0
cfg.algo.safe_controller.safe_algo.control_weight = [
1.0, 1.0, 1.0, # Waist joints
1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, # Left arm joints
1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, # Right arm joints
# Locomotion joints are omitted for fixed-base configuration
]
# Define the minimum distance to maintain from the environment
cfg.algo.safe_controller.safety_index.min_distance["environment"] = 0.1
# Select metrics to log during execution
cfg.metric_selection.dist_robot_to_env = True
Finally, initialize and run the pipeline:
# Create the pipeline instance with the specified configuration
pipeline = Pipeline(cfg)
# Run the pipeline
pipeline.run()
Environment wrapper aligning with env-algo structure. Composed of the following two modules.
Task class, receiving additional sensory data and generating objectives. Returns global info (e.g., robot base in world frame). Task runs for a maximal number of steps (-1 for continuous tasks). Currently supported tasks are listed below:
Task Class | Description |
---|---|
G1TeleopSimTask | Obstacle and robot goals can be controlled online via keyboard input |
G1BenchmarkTask | Obstacle and robot goals follow predefined trajectories |
Ultimate interface to the robot for both sim and real. Each agent implements robot-specific interfaces for receiving observations (e.g., robot states, sensory data) and publishing control (e.g., robot joint positions) for both simulation and real robots. Returns local info (e.g., robot state). Global info can also be returned if available (e.g., global localization by robot). Currently supported agents are listed below:
Agent Class | Description |
---|---|
G1RealAgent | Supports deployment on a real robot using the Unitree G1 SDK |
G1MujocoAgent | Supports simulation in the MuJoCo environment |
Algorithm wrapper aligning with env-algo structure. Composed of the following two modules if model-based safe control is used.
Policies fulfilling task-specific objectives. Currently supported policies are listed below:
Policy Class | Description |
---|---|
G1TeleopPIDPolicy | PID-based reference control for teleoperation tasks |
G1BenchmarkPIDPolicy | PID-based reference control for benchmark tasks |
safe_algo
: core module implementing safe control methods and energy functions.safe_controller
: interface to safe control algorithms.
Currently supported safe algorithms are listed below:
Safe Algorithm Class | Description |
---|---|
BasicSafeSetAlgorithm | Safe Set Algorithm(SSA) based safe controller |
RelaxedSafeSetAlgorithm | SSA based safe controller with slack variables |
BasicControlBarrierFunction | Control Barrier Function (CBF) based safe controller |
RelaxedControlBarrierFunction | CBF based safe controller with slack variables |
BasicSublevelSafeSetAlgorithm | Sublevel Safe Set Algorithm (SSS) based safe controller |
RelaxedSublevelSafeSetAlgorithm | SSS based safe controller with slack variables |
BasicPotentialFieldMethod | Potential Field Method(PFM) based safe controller |
BasicSlidingModeAlgorithm | Sliding Mode Algorithm(SMA) based safe controller |
All currently supported algorithms are based on energy functions. Among them, SSA, CBF, and SSS are optimization-based methods, while SMA and PFM are not. In SPARK, we provide a set of built-in energy functions—referred to as safety indices—to support these safety-focused algorithms. The currently supported safety indices are listed below:
Safety Index Class | Dynamic Order | Computation Method | Supported Collision Geometry |
---|---|---|---|
FirstOrderCollisionSafetyIndex | 1 | Analytical | Sphere |
FirstOrderCollisionSafetyIndexApprox | 1 | Central Difference | Sphere + Box |
SecondOrderCollisionSafetyIndex | 2 | Analytical | Sphere |
SecondOrderCollisionSafetyIndexApprox | 2 | Central Difference | Sphere + Box |
SecondOrderNNCollisionSafetyIndex | 2 | Neural Network | Sphere |
For end-to-end safe algorithms, set safe_controller
in pipeline configuration to ByPassSafeControl
and implement safe algorithms in spark_policy
. An example of disabling safe_controller
is
python example/run_g1_unsafe_teleop_sim.py
The script is essentially Safe G1 teleoperation without safe control module.
Robot library containing robot config (e.g., state, dofs, urdf). Currently supported safe algorithms are listed below:
Robot Config Class | Kinematics Class | Dynamic Order | Num of DoFs | State Dimension | Control Dimension |
---|---|---|---|---|---|
G1RightArmDynamic1Config | G1RightArmKinematics | 1 | 7 | 7 | 7 |
G1RightArmDynamic2Config | G1RightArmKinematics | 2 | 7 | 14 | 7 |
G1FixedBaseDynamic1Config | G1FixedBaseKinematics | 1 | 17 | 17 | 17 |
G1FixedBaseDynamic2Config | G1FixedBaseKinematics | 2 | 17 | 34 | 17 |
G1MobileBaseDynamic1Config | G1MobileBaseKinematics | 1 | 20 | 20 | 20 |
G1MobileBaseDynamic2Config | G1MobileBaseKinematics | 2 | 20 | 40 | 20 |
G1SportModeDynamic1Config | G1MobileBaseKinematics | 1 | 20 | 20 | 20 |
G1SportModeDynamic2Config | G1MobileBaseKinematics | 2 | 20 | 40 | 20 |
Each robot config is named as Robot Type
+ Dynamics
RightArm
: Includes only the 7 DoFs of the right arm.
FixedBase
Includes both arms and 3 DoFs of the waist, totaling 17 DoFs.
MobileBase
: Wheeled dual-arm manipulator with 3 additional base DoFs — 2D X, 2D Y, and yaw.
SportMode
: Legged dual-arm manipulator with 3 additional base DoFs — 2D X, 2D Y, and yaw.
First-Order Dynamics(Dynamic1)
: Modeled as a single integrator, where the state includes only the positions of the degrees of freedom (DoFs), and the control input is the joint velocity.
Second-Order Dynamics(Dynamic2)
: Modeled as a double integrator, where the state includes both the positions and velocities of the DoFs, and the control input is the joint acceleration.
SportMode uses the same control system as MobileBase, but the base movement (X, Y, yaw) is executed via the lower body using a learning-based policy (see Unitree RL Gym). This provides a more realistic scenario for mobile safety control.
Top level pipelines for safe robotic tasks. Pipeline runs for a maximal number of steps (-1 for unlimited). When env is done, pipeline can choose to reset the env or exit.
Pipeline Class | Task | Policy | Safety | Agent |
---|---|---|---|---|
G1SafeTeleopPipeline | Hands-only teleop; obstacles (ROS, debug) | IK + PID | SSA/CBF/etc. | G1 real, G1 mujoco |
G1BenchmarkPipeline | Dynamic goal tracking with collision avoidance | IK + PID | SSA/CBF/etc. | G1 mujoco |
run with python example/run_g1_safe_teleop_sim.py
Configure the pipeline by modifying the cfg
object in the python script or modify the config file (pipeline/spark_pipeline/g1_safe_teleop/g1_safe_teleop_sim_pipeline_config.py
)
There are several use cases described below.
Three obstacles are defined by the head and two hands of a human (human obstacle). Teleoperation goals are from a human as well (human teleoperator). Human obstacle and human teleoperator can be the same person of different people, depending on how ros topics in task config are sent.
When runnig with ROS, send obstacle positions via
rostopic pub /g1_29dof/human_state std_msgs/Float64MultiArray "data: [0.0, 0.35, 0.2, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0]"
Safety behavior should be triggered.
The data format is [radius, x1, y1, z1, x2, y2, z2]
for each obstacle.
Currently, each obstacle is a sphere at x1y1z1
in robot base frame with fixed radius of 0.05.
Hence, the above safety behavior is triggered by the 1st obstacle at [0.35, 0.2, 0.0]
.
Tweak x1y1z1
to see the effect.
When running without ROS, move debug obstacle (grey) positions via keyboard. Available operations are
Arrow keys (up/down/left/right): movement in X-Y plane
E : move in Z+
Q : move in Z-
Space : switch to next obstacle
O : switch to right arm goal
P : switch to left arm goal
PAGE_UP : add obstacle
PAGE_DOWN: remove obstacle
Currently controlled obstacle is marked with grey arrow.
In the above video:
Black spheres: robot collision volume
Green spheres: tracking goal for hands
Grey spheres : obstacle
The color of robot collision volumes will change if certain constraints are active (yellow: ssa hold state, red: ssa unsafe). Critical paris of robot collision volumes and obstacles will also be connected with lines with corresponding color when constraints are active.
run with python example/run_g1_benchmark.py
Configure the pipeline by modifying the cfg
object in the python script or modify the config file (pipeline/spark_pipeline/g1_benchmark/g1_benchmark_pipeline_config.py
)
We welcome contributions from the community! If you have suggestions, encounter bugs, or wish to enhance the project, feel free to:
-
Submit an issue to report bugs or propose features.
-
Open a pull request to contribute code, documentation, or improvements.
For any questions or assistance, please reach out to Yifan Sun.