Skip to content

Implementation of the Online Adaptive CBF for safety-critical navigation for input constrained systems.

Notifications You must be signed in to change notification settings

tkkim-robot/online_adaptive_cbf

Repository files navigation

online_adaptive_cbf

This repository contains the implementation of an online adaptive framework for Control Barrier Functions (CBFs) in input-constrained nonlinear systems. The algorithm dynamically adapts CBF parameters to optimize performance while ensuring safety, particularly for robotic navigation tasks. Please see our paper "Learning to Refine Input Constrained Control Barrier Functions via Uncertainty-Aware Online Parameter Adaptation" for more details.

Features

  • Implementation of the Probabilistic Ensemble Neural Network (PENN) which offers parallelized inference without an outer for loop. The predicted output can be interpreted as a Gaussian Mixture Model (GMM). (see Kim et al.)
  • Measurement of closed-form epistemic uncertainty from the PENN model's predictions. (see Kim et al.)
  • Integration with the safe_control repository for simulating robotic navigation, offering various robot dynamics, controllers, and RGB-D type sensor simulation.
  • Implementation of the Online Adaptive ICCBF, adapting ICCBF parameters online based on the robot's current state and nearby environment.

Installation

To install this project, follow these steps:

  1. Clone the repository:

    git --recursive clone https://github.com/tkkim-robot/online_adaptive_cbf.git
    cd online_adaptive_cbf

    If you've already cloned the repository without the --recursive flag, you can initialize and update the submodules with:

    submodule update --init --recursive
  2. (Optional) Create and activate a virtual environment

  3. Install the package and its dependencies:

    python -m pip install -e .

    Or, install packages manually (see setup.py).

Getting Started

Familiarize with APIs and examples with the scripts in online_adaptive_cbf.py

Basic Example

You can run our test example by:

python online_adaptive_cbf.py

The MPC-CBF framework is implemented in our safe_control repository. It imports LocalTrackingController class and uses the mpc_cbf implementation:

from safe_control.tracking import LocalTrackingController
controller = LocalTrackingController(x_init, robot_spec,
                                control_type='mpc_cbf')

Then, it uses OnlineCBFAdapter to adapt the CBF parameters online.

online_cbf_adapter = OnlineCBFAdapter(nn_model, scaler)

for _ in range(int(tf / self.dt)):
   ret = controller.control_step()
   controller.draw_plot()

   best_gamma0, best_gamma1 = online_cbf_adapter.cbf_param_adaptation(controller)
   controller.pos_controller.cbf_param['alpha1'] = best_gamma0
   controller.pos_controller.cbf_param['alpha2'] = best_gamma1    

You can also test with compared methods:

  • Fixed CBF parameters:
    • mpc_cbf with conservatie fixed parameters: Set lower values to CBF parameters. (* MPC-CBF: An MPC controller using discrete-time CBF, ref: [1])
         controller.pos_controller.cbf_param['alpha1'] = {low value}
         controller.pos_controller.cbf_param['alpha2'] = {low value}
    • mpc_cbf with aggressive fixed parameters: Similarly, set higher values to CBF parameters.
  • Adaptive parameter methods:
    • optimal_decay_cbf_qp: A modified CBF-QP for point-wise feasibility guarantee (ref: [2])
      controller = LocalTrackingController(..., control_type='optimal_decay_cbf_qp')
    • optimal_decay_mpc_cbf: The same technique applied to MPC-CBF (ref: [3])
      controller = LocalTrackingController(..., control_type='optimal_decay_mpc_cbf')

The sample results from the basic example:

MPC-CBF w/ low parameters MPC-CBF w/ high parameters
Optimal Decay CBF-QP Optimal Decay MPC-CBF
Ours (Online Adaptive MPC-ICCBF)

The green point is the goal location, and the gray circles are the obstacles that are known a priori.

Module Breakdown

Safety Loss Density Function

The safety loss density function is designed to quantify the collision risk between the robot and obstacles. This safety loss is computed based on the robot's state and the obstacles' locations.

Mean Predicted Risk Level

Data Generation

You can use data_generation.py to collect training dataset. It will store risk_level and deadlock_time as the ground truth.

The risk_level refers to the maximum safety loss value recorded during the navigation (see the illustration below).

Safety Loss during Navigation

PENN Prediction

To train the PENN model, use the script penn/train_data.py. An example of the prediction results after training is shown below:

Mean Predicted Risk Level

You can observe that the predicted risk level becomes higher as the CBF parameter increases, the distance to the obstacle decreases, the velocity increases, and the relative angle to the obstacle becomes smaller.

Distributionally Robust CVaR

Please refer to our repository DistributionallyRobustCVaR for more details.

Visualize Prediction Results for CBF Parameters of Interest

test_plot.py provides an online plotting tool to visualize the predicted GMM distribution of the candidate CBF parameters. Here is the example of visualizing the predicted risk_level with three candidates, without adapting the paremeters.

Single Obstacle Multiple Obstacles

Citing

If you find this repository useful, please consider citing our paper:

@inproceedings{kim2024learning, 
    author    = {Taekyung Kim and Robin Inho Kee and Dimitra Panagou},
    title     = {Learning to Refine Input Constrained Control Barrier Functions via Uncertainty-Aware Online Parameter Adaptation}, 
    booktitle = {{arXiv} preprint {arXiv}:2409.14616},
    shorttitle = {Online-Adaptive-CBF},
    year      = {2024}
}

Related Works

Here are some related projects/codes that you might be interested:

  • Visibility-Aware RRT*: Safety-critical Global Path Planning (GPP) using Visibility Control Barrier Functions

  • UGV Experiments with ROS2: Environmental setup for rovers using PX4, ros2 humble, Vicon MoCap, and NVIDIA VSLAM + NvBlox