Skip to content

Commit

Permalink
Fix errors in the docs
Browse files Browse the repository at this point in the history
  • Loading branch information
amacati committed Oct 17, 2024
1 parent d2ebb67 commit 81b6bd4
Show file tree
Hide file tree
Showing 12 changed files with 150 additions and 58 deletions.
73 changes: 72 additions & 1 deletion docs/challenge/simulation.rst
Original file line number Diff line number Diff line change
@@ -1,2 +1,73 @@
Simulation
==========
==========

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.

Difficulty Levels
-----------------

The challenge is divided into different difficulty levels, each specified by a TOML configuration file. These levels progressively increase in complexity:

.. list-table::
:header-rows: 1
:widths: 20 10 15 20 15 20

* - Evaluation Scenario
- Constraints
- Rand. Inertial Properties
- Randomized Obstacles, Gates
- Rand. Between Episodes
- Notes
* - Level 0 (config/level0.toml)
- Yes
- No
- No
- No
- Perfect knowledge
* - Level 1 (config/level1.toml)
- Yes
- Yes
- No
- No
- Adaptive
* - Level 2 (config/level2.toml)
- Yes
- Yes
- Yes
- No
- Learning, re-planning
* - Level 3 (config/level3.toml)
- Yes
- Yes
- Yes
- Yes
- Robustness
* - sim2real
- Yes
- Real-life hardware
- Yes
- No
- Sim2real transfer

.. note::
"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.

You may use the easier scenarios to develop and debug your controller. However, the final evaluation will be on the hardest scenario (Level 3).

Switching Between Configurations
--------------------------------

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:

.. code-block:: bash
python scripts/sim.py --config config/level3.toml
To use your own controller, you can pass the path to your controller script as the `--controller` argument. For example:

.. code-block:: bash
python scripts/sim.py --config config/level3.toml --controller my_controller.py
.. note::
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.
10 changes: 5 additions & 5 deletions lsy_drone_racing/control/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,11 @@
To give you an idea of what you need to do, we also include some example implementations:
- BaseController: The abstract base class defining the interface for all controllers.
- PPO Controller: An example implementation using a pre-trained Proximal Policy Optimization (PPO)
model.
- Trajectory Controller: A controller that follows a pre-defined trajectory using cubic spline
interpolation.
* :class:`~.BaseController`: The abstract base class defining the interface for all controllers.
* :class:`PPOController <lsy_drone_racing.control.ppo_controller.PPOController>`: An example
implementation using a pre-trained Proximal Policy Optimization (PPO) model.
* :class:`PPOController <lsy_drone_racing.control.trajectory_controller.TrajectoryController>`: A
controller that follows a pre-defined trajectory using cubic spline interpolation.
"""

from lsy_drone_racing.control.controller import BaseController
Expand Down
5 changes: 3 additions & 2 deletions lsy_drone_racing/control/controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,9 @@
from that, you are free to add any additional methods, attributes, or classes to your controller.
As an example, you could load the weights of a neural network in the constructor and use it to
compute the control commands in the `compute_control` method. You could also use the `step_callback`
method to update the controller state at runtime.
compute the control commands in the :meth:`compute_control <.BaseController.compute_control>`
method. You could also use the :meth:`step_callback <.BaseController.step_callback>` method to
update the controller state at runtime.
Note:
You can only define one controller class in a single file. Otherwise we will not be able to
Expand Down
11 changes: 10 additions & 1 deletion lsy_drone_racing/control/ppo_controller.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,13 @@
"""Example implementation of a controller using a pre-trained PPO model."""
"""Example implementation of a controller using a pre-trained PPO model.
The controller loads the pre-trained weights of the policy and uses it to compute the next action
based on the current observation.
.. note::
You need to install the
`stable-baselines3 <https://stable-baselines3.readthedocs.io/en/master/>`_ library to use this
controller.
"""

from __future__ import annotations # Python 3.10 type hints

Expand Down
11 changes: 10 additions & 1 deletion lsy_drone_racing/control/trajectory_controller.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,13 @@
"""Controller that follows a pre-defined trajectory."""
"""Controller that follows a pre-defined trajectory.
It uses a cubic spline interpolation to generate a smooth trajectory through a series of waypoints.
At each time step, the controller computes the next desired position by evaluating the spline.
.. note::
The waypoints are hard-coded in the controller for demonstration purposes. In practice, you
would need to generate the splines adaptively based on the track layout, and recompute the
trajectory if you receive updated gate and obstacle poses.
"""

from __future__ import annotations # Python 3.10 type hints

Expand Down
18 changes: 8 additions & 10 deletions lsy_drone_racing/envs/drone_racing_deploy_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,19 @@
This module provides environments for deploying drone racing algorithms on physical hardware,
mirroring the functionality of the simulation environments in the
:mod:~lsy_drone_racing.envs.drone_racing module.
:mod:`~lsy_drone_racing.envs.drone_racing_env` module.
Key components:
- :class:~.DroneRacingDeployEnv: A Gymnasium environment for controlling a real Crazyflie drone in a
physical race track, using Vicon motion capture for positioning.
- :class:~.DroneRacingThrustDeployEnv: A variant of DroneRacingDeployEnv that uses collective thrust
and attitude commands for control.
* :class:`~.DroneRacingDeployEnv`: A Gymnasium environment for controlling a real Crazyflie drone in
a physical race track, using Vicon motion capture for positioning.
* :class:`~.DroneRacingThrustDeployEnv`: A variant of :class:`~.DroneRacingDeployEnv` that uses
collective thrust and attitude commands for control.
These environments maintain consistent interfaces with their simulation counterparts
(:class:~lsy_drone_racing.envs.drone_racing_env.DroneRacingEnv and
:class:~lsy_drone_racing.envs.drone_racing_thrust_env.DroneRacingThrustEnv), allowing for seamless
transition from simulation to real-world deployment. They handle the complexities of interfacing
with physical hardware while providing the same observation and action spaces as the simulation
environments.
(:class:`~.DroneRacingEnv` and :class:`~.DroneRacingThrustEnv`), allowing for seamless transition
from simulation to real-world deployment. They handle the complexities of interfacing with physical
hardware while providing the same observation and action spaces as the simulation environments.
The module integrates with ROS, Crazyswarm, and Vicon systems to enable real-world drone control and
tracking in a racing scenario.
Expand Down
28 changes: 15 additions & 13 deletions lsy_drone_racing/envs/drone_racing_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,23 @@
between the drone racing simulation and the user's control algorithms.
It serves as a bridge between the high-level race control and the low-level drone physics
simulation. The environments defined here (DroneRacingEnv and DroneRacingThrustEnv) expose a common
interface for all controller types, allowing for easy integration and testing of different control
algorithms, comparison of control strategies, and deployment on our hardware.
simulation. The environments defined here
(:class:`~.DroneRacingEnv` and :class:`~.DroneRacingThrustEnv`) expose a common interface for all
controller types, allowing for easy integration and testing of different control algorithms,
comparison of control strategies, and deployment on our hardware.
Key roles in the project:
1. Abstraction Layer: Provides a standardized Gymnasium interface for interacting with the drone
racing simulation, abstracting away the underlying physics engine.
2. State Management: Handles the tracking of race progress, gate passages, and termination
conditions.
3. Observation Processing: Manages the transformation of raw simulation data into structured
observations suitable for control algorithms.
4. Action Interpretation: Translates high-level control commands into appropriate inputs for the
underlying simulation.
5. Configuration Interface: Allows for easy customization of race scenarios, environmental
conditions, and simulation parameters.
* Abstraction Layer: Provides a standardized Gymnasium interface for interacting with the
drone racing simulation, abstracting away the underlying physics engine.
* State Management: Handles the tracking of race progress, gate passages, and termination
conditions.
* Observation Processing: Manages the transformation of raw simulation data into structured
observations suitable for control algorithms.
* Action Interpretation: Translates high-level control commands into appropriate inputs for the
underlying simulation.
* Configuration Interface: Allows for easy customization of race scenarios, environmental
conditions, and simulation parameters.
"""

from __future__ import annotations
Expand Down
17 changes: 9 additions & 8 deletions lsy_drone_racing/sim/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,20 +3,21 @@
This module provides a high-fidelity simulation setup for quadrotor drones, particularly focused on
drone racing scenarios. It includes:
- A physics-based simulation using PyBullet
- Detailed drone dynamics and control models
- Symbolic representations for dynamics, observations, and cost functions
- Configurable noise and disturbance models
* A physics-based simulation using PyBullet
* Detailed drone dynamics and control models
* Symbolic representations for dynamics, observations, and cost functions
* Configurable noise and disturbance models
The simulation environment allows for realistic modeling of drone behavior, including aerodynamics,
motor dynamics, and sensor characteristics. It supports both high-fidelity physics simulations and
analytical models for predictable dynamics.
Key components of the simulation include:
- Drone state representation and dynamics
- An exchangeable physics backend with PyBullet as visualizer
- Customizable environmental factors and disturbances
- Symbolic models for advanced control techniques
* Drone state representation and dynamics
* An exchangeable physics backend with PyBullet as visualizer
* Customizable environmental factors and disturbances
* Symbolic models for advanced control techniques
The physics backend utilizes PyBullet by default for rigid body dynamics simulation, providing
accurate modeling of collisions, constraints, and multi-body interactions. It can also be replaced
Expand Down
10 changes: 5 additions & 5 deletions lsy_drone_racing/sim/drone.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,11 @@
The Drone class is a core component of the simulation environment and is heavily utilized
in the sim.py module. It handles various aspects of drone behavior, including:
- Initialization of drone parameters and firmware
- Management of drone state and control inputs
- Implementation of controller logic
- Conversion between different units (e.g., thrust to RPM)
- Handling of sensor data and low-pass filtering
* Initialization of drone parameters and firmware
* Management of drone state and control inputs
* Implementation of controller logic
* Conversion between different units (e.g., thrust to RPM)
* Handling of sensor data and low-pass filtering
This module also includes the DroneParams dataclass, which encapsulates the physical
and inferred parameters of the Crazyflie 2.1 drone.
Expand Down
10 changes: 5 additions & 5 deletions lsy_drone_racing/sim/sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,11 @@
Features:
- PyBullet-based physics simulation
- Configurable drone parameters and initial conditions
- Support for a single drone (multi-drone support not yet implemented)
- Disturbance and randomization options
- Integration with symbolic models
* PyBullet-based physics simulation
* Configurable drone parameters and initial conditions
* Support for a single drone (multi-drone support not yet implemented)
* Disturbance and randomization options
* Integration with symbolic models
The simulation is derived from the gym-pybullet-drones project:
https://github.com/utiasDSL/gym-pybullet-drones
Expand Down
9 changes: 5 additions & 4 deletions lsy_drone_racing/sim/symbolic.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,11 @@
This module provides functionality to create symbolic representations of the drone dynamics,
observations, and cost functions using CasADi. It includes:
- SymbolicModel: A class that encapsulates the symbolic representation of the drone model,
including dynamics, observations, and cost functions.
- symbolic: A function that creates a SymbolicModel instance for a given drone configuration.
- Helper functions for creating rotation matrices and other mathematical operations.
* :class:`~.SymbolicModel`: A class that encapsulates the symbolic representation of the drone
model, including dynamics, observations, and cost functions.
* :func:`symbolic <lsy_drone_racing.sim.symbolic.symbolic>`: A function that creates a
:class:`~.SymbolicModel` instance for a given drone configuration.
* Helper functions for creating rotation matrices and other mathematical operations.
The symbolic models created by this module can be used for various control and estimation tasks,
such as model predictive control (MPC) or state estimation. They provide a convenient way to work
Expand Down
6 changes: 3 additions & 3 deletions lsy_drone_racing/vicon.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
It defines the Vicon class, which handles communication with the Vicon system through ROS messages.
The Vicon class is responsible for:
- Tracking the drone and other objects (gates, obstacles) in the racing environment.
- Providing real-time pose (position and orientation) data for tracked objects.
- Calculating velocities and angular velocities based on pose changes.
* Tracking the drone and other objects (gates, obstacles) in the racing environment.
* Providing real-time pose (position and orientation) data for tracked objects.
* Calculating velocities and angular velocities based on pose changes.
This module is necessary to provide the real-world positioning data for the drone and race track
elements.
Expand Down

0 comments on commit 81b6bd4

Please sign in to comment.