Skip to content

Commit 81b6bd4

Browse files
committed
Fix errors in the docs
1 parent d2ebb67 commit 81b6bd4

12 files changed

+150
-58
lines changed

docs/challenge/simulation.rst

+72-1
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,73 @@
11
Simulation
2-
==========
2+
==========
3+
4+
The first part of the challenge is to complete the race track in simulation. To that end, we provide a high-fidelity simulator with interfaces that are identical to the real-world setup. We use PyBullet as the underlying simulator to model the physics of the drone and to render the environment.
5+
6+
Difficulty Levels
7+
-----------------
8+
9+
The challenge is divided into different difficulty levels, each specified by a TOML configuration file. These levels progressively increase in complexity:
10+
11+
.. list-table::
12+
:header-rows: 1
13+
:widths: 20 10 15 20 15 20
14+
15+
* - Evaluation Scenario
16+
- Constraints
17+
- Rand. Inertial Properties
18+
- Randomized Obstacles, Gates
19+
- Rand. Between Episodes
20+
- Notes
21+
* - Level 0 (config/level0.toml)
22+
- Yes
23+
- No
24+
- No
25+
- No
26+
- Perfect knowledge
27+
* - Level 1 (config/level1.toml)
28+
- Yes
29+
- Yes
30+
- No
31+
- No
32+
- Adaptive
33+
* - Level 2 (config/level2.toml)
34+
- Yes
35+
- Yes
36+
- Yes
37+
- No
38+
- Learning, re-planning
39+
* - Level 3 (config/level3.toml)
40+
- Yes
41+
- Yes
42+
- Yes
43+
- Yes
44+
- Robustness
45+
* - sim2real
46+
- Yes
47+
- Real-life hardware
48+
- Yes
49+
- No
50+
- Sim2real transfer
51+
52+
.. note::
53+
"Rand. Between Episodes" (governed by argument `reseed_on_reset`) determines whether randomized properties and positions vary or are kept constant (by re-seeding the random number generator on each `env.reset()`) across episodes.
54+
55+
You may use the easier scenarios to develop and debug your controller. However, the final evaluation will be on the hardest scenario (Level 3).
56+
57+
Switching Between Configurations
58+
--------------------------------
59+
60+
You can choose which configuration to use by changing the `--config` command line option. For example, to run the example controller on the hardest scenario, use the following command:
61+
62+
.. code-block:: bash
63+
64+
python scripts/sim.py --config config/level3.toml
65+
66+
To use your own controller, you can pass the path to your controller script as the `--controller` argument. For example:
67+
68+
.. code-block:: bash
69+
70+
python scripts/sim.py --config config/level3.toml --controller my_controller.py
71+
72+
.. note::
73+
You can also write your controller file directly into the config files located in the `config` folder. That way, you don't need to specify the controller script when running the simulation, and the controller will be used in the automated challenge evaluation.

lsy_drone_racing/control/__init__.py

+5-5
Original file line numberDiff line numberDiff line change
@@ -6,11 +6,11 @@
66
77
To give you an idea of what you need to do, we also include some example implementations:
88
9-
- BaseController: The abstract base class defining the interface for all controllers.
10-
- PPO Controller: An example implementation using a pre-trained Proximal Policy Optimization (PPO)
11-
model.
12-
- Trajectory Controller: A controller that follows a pre-defined trajectory using cubic spline
13-
interpolation.
9+
* :class:`~.BaseController`: The abstract base class defining the interface for all controllers.
10+
* :class:`PPOController <lsy_drone_racing.control.ppo_controller.PPOController>`: An example
11+
implementation using a pre-trained Proximal Policy Optimization (PPO) model.
12+
* :class:`PPOController <lsy_drone_racing.control.trajectory_controller.TrajectoryController>`: A
13+
controller that follows a pre-defined trajectory using cubic spline interpolation.
1414
"""
1515

1616
from lsy_drone_racing.control.controller import BaseController

lsy_drone_racing/control/controller.py

+3-2
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,9 @@
55
from that, you are free to add any additional methods, attributes, or classes to your controller.
66
77
As an example, you could load the weights of a neural network in the constructor and use it to
8-
compute the control commands in the `compute_control` method. You could also use the `step_callback`
9-
method to update the controller state at runtime.
8+
compute the control commands in the :meth:`compute_control <.BaseController.compute_control>`
9+
method. You could also use the :meth:`step_callback <.BaseController.step_callback>` method to
10+
update the controller state at runtime.
1011
1112
Note:
1213
You can only define one controller class in a single file. Otherwise we will not be able to

lsy_drone_racing/control/ppo_controller.py

+10-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,13 @@
1-
"""Example implementation of a controller using a pre-trained PPO model."""
1+
"""Example implementation of a controller using a pre-trained PPO model.
2+
3+
The controller loads the pre-trained weights of the policy and uses it to compute the next action
4+
based on the current observation.
5+
6+
.. note::
7+
You need to install the
8+
`stable-baselines3 <https://stable-baselines3.readthedocs.io/en/master/>`_ library to use this
9+
controller.
10+
"""
211

312
from __future__ import annotations # Python 3.10 type hints
413

lsy_drone_racing/control/trajectory_controller.py

+10-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,13 @@
1-
"""Controller that follows a pre-defined trajectory."""
1+
"""Controller that follows a pre-defined trajectory.
2+
3+
It uses a cubic spline interpolation to generate a smooth trajectory through a series of waypoints.
4+
At each time step, the controller computes the next desired position by evaluating the spline.
5+
6+
.. note::
7+
The waypoints are hard-coded in the controller for demonstration purposes. In practice, you
8+
would need to generate the splines adaptively based on the track layout, and recompute the
9+
trajectory if you receive updated gate and obstacle poses.
10+
"""
211

312
from __future__ import annotations # Python 3.10 type hints
413

lsy_drone_racing/envs/drone_racing_deploy_env.py

+8-10
Original file line numberDiff line numberDiff line change
@@ -2,21 +2,19 @@
22
33
This module provides environments for deploying drone racing algorithms on physical hardware,
44
mirroring the functionality of the simulation environments in the
5-
:mod:~lsy_drone_racing.envs.drone_racing module.
5+
:mod:`~lsy_drone_racing.envs.drone_racing_env` module.
66
77
Key components:
88
9-
- :class:~.DroneRacingDeployEnv: A Gymnasium environment for controlling a real Crazyflie drone in a
10-
physical race track, using Vicon motion capture for positioning.
11-
- :class:~.DroneRacingThrustDeployEnv: A variant of DroneRacingDeployEnv that uses collective thrust
12-
and attitude commands for control.
9+
* :class:`~.DroneRacingDeployEnv`: A Gymnasium environment for controlling a real Crazyflie drone in
10+
a physical race track, using Vicon motion capture for positioning.
11+
* :class:`~.DroneRacingThrustDeployEnv`: A variant of :class:`~.DroneRacingDeployEnv` that uses
12+
collective thrust and attitude commands for control.
1313
1414
These environments maintain consistent interfaces with their simulation counterparts
15-
(:class:~lsy_drone_racing.envs.drone_racing_env.DroneRacingEnv and
16-
:class:~lsy_drone_racing.envs.drone_racing_thrust_env.DroneRacingThrustEnv), allowing for seamless
17-
transition from simulation to real-world deployment. They handle the complexities of interfacing
18-
with physical hardware while providing the same observation and action spaces as the simulation
19-
environments.
15+
(:class:`~.DroneRacingEnv` and :class:`~.DroneRacingThrustEnv`), allowing for seamless transition
16+
from simulation to real-world deployment. They handle the complexities of interfacing with physical
17+
hardware while providing the same observation and action spaces as the simulation environments.
2018
2119
The module integrates with ROS, Crazyswarm, and Vicon systems to enable real-world drone control and
2220
tracking in a racing scenario.

lsy_drone_racing/envs/drone_racing_env.py

+15-13
Original file line numberDiff line numberDiff line change
@@ -4,21 +4,23 @@
44
between the drone racing simulation and the user's control algorithms.
55
66
It serves as a bridge between the high-level race control and the low-level drone physics
7-
simulation. The environments defined here (DroneRacingEnv and DroneRacingThrustEnv) expose a common
8-
interface for all controller types, allowing for easy integration and testing of different control
9-
algorithms, comparison of control strategies, and deployment on our hardware.
7+
simulation. The environments defined here
8+
(:class:`~.DroneRacingEnv` and :class:`~.DroneRacingThrustEnv`) expose a common interface for all
9+
controller types, allowing for easy integration and testing of different control algorithms,
10+
comparison of control strategies, and deployment on our hardware.
1011
1112
Key roles in the project:
12-
1. Abstraction Layer: Provides a standardized Gymnasium interface for interacting with the drone
13-
racing simulation, abstracting away the underlying physics engine.
14-
2. State Management: Handles the tracking of race progress, gate passages, and termination
15-
conditions.
16-
3. Observation Processing: Manages the transformation of raw simulation data into structured
17-
observations suitable for control algorithms.
18-
4. Action Interpretation: Translates high-level control commands into appropriate inputs for the
19-
underlying simulation.
20-
5. Configuration Interface: Allows for easy customization of race scenarios, environmental
21-
conditions, and simulation parameters.
13+
14+
* Abstraction Layer: Provides a standardized Gymnasium interface for interacting with the
15+
drone racing simulation, abstracting away the underlying physics engine.
16+
* State Management: Handles the tracking of race progress, gate passages, and termination
17+
conditions.
18+
* Observation Processing: Manages the transformation of raw simulation data into structured
19+
observations suitable for control algorithms.
20+
* Action Interpretation: Translates high-level control commands into appropriate inputs for the
21+
underlying simulation.
22+
* Configuration Interface: Allows for easy customization of race scenarios, environmental
23+
conditions, and simulation parameters.
2224
"""
2325

2426
from __future__ import annotations

lsy_drone_racing/sim/__init__.py

+9-8
Original file line numberDiff line numberDiff line change
@@ -3,20 +3,21 @@
33
This module provides a high-fidelity simulation setup for quadrotor drones, particularly focused on
44
drone racing scenarios. It includes:
55
6-
- A physics-based simulation using PyBullet
7-
- Detailed drone dynamics and control models
8-
- Symbolic representations for dynamics, observations, and cost functions
9-
- Configurable noise and disturbance models
6+
* A physics-based simulation using PyBullet
7+
* Detailed drone dynamics and control models
8+
* Symbolic representations for dynamics, observations, and cost functions
9+
* Configurable noise and disturbance models
1010
1111
The simulation environment allows for realistic modeling of drone behavior, including aerodynamics,
1212
motor dynamics, and sensor characteristics. It supports both high-fidelity physics simulations and
1313
analytical models for predictable dynamics.
1414
1515
Key components of the simulation include:
16-
- Drone state representation and dynamics
17-
- An exchangeable physics backend with PyBullet as visualizer
18-
- Customizable environmental factors and disturbances
19-
- Symbolic models for advanced control techniques
16+
17+
* Drone state representation and dynamics
18+
* An exchangeable physics backend with PyBullet as visualizer
19+
* Customizable environmental factors and disturbances
20+
* Symbolic models for advanced control techniques
2021
2122
The physics backend utilizes PyBullet by default for rigid body dynamics simulation, providing
2223
accurate modeling of collisions, constraints, and multi-body interactions. It can also be replaced

lsy_drone_racing/sim/drone.py

+5-5
Original file line numberDiff line numberDiff line change
@@ -8,11 +8,11 @@
88
The Drone class is a core component of the simulation environment and is heavily utilized
99
in the sim.py module. It handles various aspects of drone behavior, including:
1010
11-
- Initialization of drone parameters and firmware
12-
- Management of drone state and control inputs
13-
- Implementation of controller logic
14-
- Conversion between different units (e.g., thrust to RPM)
15-
- Handling of sensor data and low-pass filtering
11+
* Initialization of drone parameters and firmware
12+
* Management of drone state and control inputs
13+
* Implementation of controller logic
14+
* Conversion between different units (e.g., thrust to RPM)
15+
* Handling of sensor data and low-pass filtering
1616
1717
This module also includes the DroneParams dataclass, which encapsulates the physical
1818
and inferred parameters of the Crazyflie 2.1 drone.

lsy_drone_racing/sim/sim.py

+5-5
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,11 @@
55
66
Features:
77
8-
- PyBullet-based physics simulation
9-
- Configurable drone parameters and initial conditions
10-
- Support for a single drone (multi-drone support not yet implemented)
11-
- Disturbance and randomization options
12-
- Integration with symbolic models
8+
* PyBullet-based physics simulation
9+
* Configurable drone parameters and initial conditions
10+
* Support for a single drone (multi-drone support not yet implemented)
11+
* Disturbance and randomization options
12+
* Integration with symbolic models
1313
1414
The simulation is derived from the gym-pybullet-drones project:
1515
https://github.com/utiasDSL/gym-pybullet-drones

lsy_drone_racing/sim/symbolic.py

+5-4
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,11 @@
33
This module provides functionality to create symbolic representations of the drone dynamics,
44
observations, and cost functions using CasADi. It includes:
55
6-
- SymbolicModel: A class that encapsulates the symbolic representation of the drone model,
7-
including dynamics, observations, and cost functions.
8-
- symbolic: A function that creates a SymbolicModel instance for a given drone configuration.
9-
- Helper functions for creating rotation matrices and other mathematical operations.
6+
* :class:`~.SymbolicModel`: A class that encapsulates the symbolic representation of the drone
7+
model, including dynamics, observations, and cost functions.
8+
* :func:`symbolic <lsy_drone_racing.sim.symbolic.symbolic>`: A function that creates a
9+
:class:`~.SymbolicModel` instance for a given drone configuration.
10+
* Helper functions for creating rotation matrices and other mathematical operations.
1011
1112
The symbolic models created by this module can be used for various control and estimation tasks,
1213
such as model predictive control (MPC) or state estimation. They provide a convenient way to work

lsy_drone_racing/vicon.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -3,9 +3,9 @@
33
It defines the Vicon class, which handles communication with the Vicon system through ROS messages.
44
The Vicon class is responsible for:
55
6-
- Tracking the drone and other objects (gates, obstacles) in the racing environment.
7-
- Providing real-time pose (position and orientation) data for tracked objects.
8-
- Calculating velocities and angular velocities based on pose changes.
6+
* Tracking the drone and other objects (gates, obstacles) in the racing environment.
7+
* Providing real-time pose (position and orientation) data for tracked objects.
8+
* Calculating velocities and angular velocities based on pose changes.
99
1010
This module is necessary to provide the real-world positioning data for the drone and race track
1111
elements.

0 commit comments

Comments
 (0)