Skip to content

Commit

Permalink
Initial release
Browse files Browse the repository at this point in the history
  • Loading branch information
danielpmorton committed Dec 10, 2024
1 parent 3c7684f commit e89c94f
Show file tree
Hide file tree
Showing 70 changed files with 7,564 additions and 0 deletions.
39 changes: 39 additions & 0 deletions .github/workflows/docs.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
name: build-documentation

on:
# Allow us to manually build the documentation when desired
workflow_dispatch:
# Schedule the documentation to automatically build weekly if we forget to update it
# (Uncomment the following lines to re-enable this)
# schedule:
# - cron: '32 13 * * 1' # Mondays at 9:32 AM Eastern (13:32 UTC) (launch time for Apollo 11 :D)

permissions:
contents: write
jobs:
deploy:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Configure Git Credentials
run: |
git config user.name github-actions[bot]
git config user.email 41898282+github-actions[bot]@users.noreply.github.com
- uses: actions/setup-python@v5
with:
python-version: 3.x
- run: echo "cache_id=$(date --utc '+%V')" >> $GITHUB_ENV


- uses: actions/cache@v4
with:
key: mkdocs-material-${{ env.cache_id }}
path: .cache
restore-keys: |
mkdocs-material-
- run: pip install \
mkdocs-material \
mkdocstrings[python]
# TODO: Figure out if we need to install all dependencies or just the docs dependencies
# - run: pip install -e .[docs]
- run: mkdocs gh-deploy --force
5 changes: 5 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
*.egg-info/*
__pycache__
.python-version
site/
.vscode/
21 changes: 21 additions & 0 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
MIT License

Copyright (c) 2024 Daniel Morton

Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
191 changes: 191 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,191 @@
# CBFpy: Control Barrier Functions in Python and Jax

CBFpy is an easy-to-use and high-performance framework for constructing and solving Control Barrier Functions (CBFs) and Control Lyapunov Functions (CLFs), using [Jax](https://github.com/google/jax) for:

- Just-in-time compilation
- Accelerated linear algebra operations with [XLA](https://openxla.org/xla)
- Automatic differentiation

For API reference, see the following [documentation](https://danielpmorton.github.io/cbfpy)

If you use CBFpy in your research, please use the following citation:

```
@software{Morton_CBFpy_2024,
author = {Morton, Daniel},
license = {MIT},
title = {{CBFpy: Control Barrier Functions in Python and Jax}},
url = {https://github.com/danielpmorton/cbfpy},
version = {0.0.1},
month = Dec,
year = {2024}
}
```

## Installation

### From PyPI

```
pip install cbfpy
```

### From source

A virtual environment is optional, but highly recommended. For `pyenv` installation instructions, see [here](https://danielpmorton.github.io/cbfpy/pyenv).

```
git clone https://github.com/danielpmorton/cbfpy
cd cbfpy
pip install -e ".[examples]"
```
The `[examples]` tag installs all of the required packages for development and running the examples. The pure `cbfpy` functionality does not require these extra packages though. If you want to contribute to the repo, you can also include the `[dev]` dependencies.

If you are working on Apple silicon and have issues installing Jax, the following threads may be useful: [[1]](https://stackoverflow.com/questions/68327863/importing-jax-fails-on-mac-with-m1-chip), [[2]](https://github.com/jax-ml/jax/issues/5501#issuecomment-955590288)

## Usage:

#### Example: A point-mass robot in 1D with an applied force and a positional barrier

For this problem, the state $z$ is defined as the position and velocity of the robot,

$$z = [x, \dot{x}]$$

So, the state derivative $\dot{z}$ is therefore

$$\dot{z} = [\dot{x}, \ddot{x}]$$

And the control input is the applied force in the $x$ direction:

$$u = F_{x}$$

The dynamics can be expressed as follows (with $m$ denoting the robot's mass):

$$\dot{z} = \begin{bmatrix}0 & 1 \\
0 & 0
\end{bmatrix}z +
\begin{bmatrix}0 \\
1/m
\end{bmatrix} u$$

This is a control affine system, since the dynamics can be expressed as

$$\dot{z} = f(z) + g(z) u$$

If the robot is controlled by some nominal (unsafe) controller, we may want to guarantee that it remains in some safe region. If we define $X_{safe} \in [x_{min}, \infty]$, we can construct a (relative-degree-2, zeroing) barrier $h$ where $h(z) \geq 0$ for any $z$ in the safe set:

$$h(z) = x - x_{min}$$

### In Code

We'll first define our problem (dynamics, barrier, and any additional parameters) in a `CBFConfig`-derived class.

We use [Jax](https://github.com/google/jax) for fast compilation of the problem. Jax can be tricky to learn at first, but luckily `cbfpy` just requires formulating your functions in `jax.numpy` which has the same familiar interface as `numpy`. These should be pure functions without side effects (for instance, modifying a class variable in `self`).

Additional tuning parameters/functions can be found in the `CBFConfig` documentation.

```python
import jax.numpy as jnp
from cbfpy import CBF, CBFConfig

# Create a config class for your problem inheriting from the CBFConfig class
class MyCBFConfig(CBFConfig):
def __init__(self):
super().__init__(
# Define the state and control dimensions
n = 2, # [x, x_dot]
m = 1, # [F_x]
# Define control limits (if desired)
u_min = None,
u_max = None,
)

# Define the control-affine dynamics functions `f` and `g` for your system
def f(self, z):
A = jnp.array([[0.0, 1.0], [0.0, 0.0]])
return A @ z

def g(self, z):
mass = 1.0
B = jnp.array([[0.0], [1.0 / mass]])
return B

# Define the barrier function `h`
# The *relative degree* of this system is 2, so, we'll use the h_2 method
def h_2(self, z):
x_min = 1.0
x = z[0]
return jnp.array([x - x_min])
```
We can then construct the CBF from our config and use it in our control loop as follows.
```python
config = MyCBFConfig()
cbf = CBF.from_config(config)

# Pseudocode
while True:
z = get_state()
z_des = get_desired_state()
u_nom = nominal_controller(z, z_des)
u = cbf.safety_filter(z, u_nom)
apply_control(u)
step()
```

## Examples

These can be found in the `examples` folder [here](https://github.com/danielpmorton/cbfpy/tree/main/cbfpy/examples)

### [Adaptive Cruise Control](https://github.com/danielpmorton/cbfpy/blob/main/cbfpy/examples/adaptive_cruise_control_demo.py)

Use a CLF-CBF to maintain a safe follow distance to the vehicle in front, while tracking a desired velocity

- State: z = [Follower velocity, Leader velocity, Follow distance] (n = 3)
- Control: u = [Follower wheel force] (m = 1)
- Relative degree: 1

![Image: Adaptive cruise control](https://raw.githubusercontent.com/danielpmorton/cbfpy/refs/heads/main/images/acc_safe.gif)

### [Point Robot Safe-Set Containment](https://github.com/danielpmorton/cbfpy/blob/main/cbfpy/examples/point_robot_demo.py)

Use a CBF to enforce that a point robot stays within a safe box, while a PD controller attempts to reduce the distance to a target position

- State: z = [Position, Velocity] (n = 6)
- Control: u = [Force] (m = 3)
- Relative degree: 2

![Image: Point robot in a safe set](https://raw.githubusercontent.com/danielpmorton/cbfpy/refs/heads/main/images/point_robot_safe.gif)

### [Point Robot Obstacle Avoidance](https://github.com/danielpmorton/cbfpy/blob/main/cbfpy/examples/point_robot_obstacle_demo.py)

Use a CBF to keep a point robot inside a safe box, while avoiding a moving obstacle. The nominal PD controller attempts to keep the robot at the origin.

- State: z = [Position, Velocity] (n = 6)
- Control: u = [Force] (m = 3)
- Relative degree: 1 + 2 (1 for obstacle avoidance, 2 for safe set containment)
- Additional data: The state of the obstacle (position and velocity)

![Image: Point robot avoiding an obstacle](https://raw.githubusercontent.com/danielpmorton/cbfpy/refs/heads/main/images/point_robot_obstacle.gif)

### [Manipulator Joint Limit Avoidance](https://github.com/danielpmorton/cbfpy/blob/main/cbfpy/examples/joint_limits_demo.py)

Use a CBF to keep a manipulator operating within its joint limits, even if a nominal joint trajectory is unsafe.

- State: z = [Joint angles] (n = 3)
- Control: u = [Joint velocities] (m = 3)
- Relative degree: 1

![Image: 3-DOF manipulator avoiding joint limits](https://raw.githubusercontent.com/danielpmorton/cbfpy/refs/heads/main/images/joint_limits.png)

### [Drone Obstacle Avoidance](https://github.com/danielpmorton/cbfpy/blob/main/cbfpy/examples/drone_demo.py)

Use a CBF to keep a drone inside a safe box, while avoiding a moving obstacle. This is similar to the "point robot obstacle avoidance" demo, but with slightly different dynamics.

- State: z = [Position, Velocity] (n = 6)
- Control: u = [Velocity] (m = 3)
- Relative degree: 1
- Additional data: The state of the obstacle (position and velocity)

This is the same CBF which was used in the ["Drone Fencing" demo](https://danielpmorton.github.io/drone_fencing/) at the Stanford Robotics center.

![Image: Quadrotor avoiding an obstacle](https://raw.githubusercontent.com/danielpmorton/cbfpy/refs/heads/main/images/drone_demo.gif)
3 changes: 3 additions & 0 deletions artifacts/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
*

!.gitignore
8 changes: 8 additions & 0 deletions cbfpy/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
import jax

jax.config.update("jax_enable_x64", True)

from cbfpy.cbfs.cbf import CBF
from cbfpy.cbfs.clf_cbf import CLFCBF
from cbfpy.config.cbf_config import CBFConfig
from cbfpy.config.clf_cbf_config import CLFCBFConfig
27 changes: 27 additions & 0 deletions cbfpy/assets/point_robot.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>

<!-- TODO inertias are definitely wrong -->

<robot name="point_robot">

<link name="base_link">
<visual>
<geometry>
<sphere radius="0.25"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</visual>
<collision>
<geometry>
<sphere radius="0.25"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</inertial>
</link>

</robot>
Loading

0 comments on commit e89c94f

Please sign in to comment.