QuadX#

Model Description#

The QuadX UAV describes a multirotor UAV in the Quad-X configuration as described by ArduPilot and PX4. It consists of four motors with implementations for cascaded PID controllers.

Variants#

Two different models of the QuadX drone are provided. This option can be selected through the drone_model parameter. The available models are:

  • cf2x (default)

  • primitive_drone

Control Modes#

The control mode of the QuadX can be changed using the Aviary.set_mode or specifically calling set_mode on the drone instance itself. Inspired by pybullet drones by University of Toronto’s Dynamic Systems Lab. The various modes available are documented below.

Class Description#

class PyFlyt.core.drones.QuadX(p: BulletClient, start_pos: ndarray, start_orn: ndarray, control_hz: int = 120, physics_hz: int = 240, drone_model: str = 'cf2x', model_dir: None | str = None, np_random: None | Generator = None, use_camera: bool = False, use_gimbal: bool = False, camera_angle_degrees: int = 20, camera_FOV_degrees: int = 90, camera_position_offset: ndarray = array([0., 0., 0.]), camera_resolution: tuple[int, int] = (128, 128), camera_fps: None | int = None)#

QuadX instance that handles everything about a quadrotor in the X configuration.

register_controller(controller_id: int, controller_constructor: type[ControlClass], base_mode: int) None#

Registers a new controller for the UAV.

Parameters:
  • controller_id (int) – controller_id

  • controller_constructor (type[ControlClass]) – controller_constructor

  • base_mode (int) – base_mode

reset() None#

Resets the vehicle to the initial state.

set_mode(mode: int) None#

Sets the current flight mode of the vehicle.

flight modes:
  • -1: m1, m2, m3, m4

  • 0: vp, vq, vr, T

  • 1: p, q, r, vz

  • 2: vp, vq, vr, z

  • 3: p, q, r, z

  • 4: u, v, vr, z

  • 5: u, v, vr, vz

  • 6: vx, vy, vr, vz

  • 7: x, y, r, z

breakdown:
  • vp, vq, vr = angular velocities

  • p, q, r = angular positions

  • u, v, w = local linear velocities

  • x, y, z = linear positions

  • vx, vy, vz = ground linear velocities

  • T = thrust

Parameters:

mode (int) – flight mode

update_control(physics_step: int) None#

Runs through controllers.

Parameters:

physics_step (int) – the current physics step

update_last(physics_step: int) None#

Updates things only at the end of Aviary.step().

Parameters:

physics_step (int) – the current physics step

update_physics() None#

Updates the physics of the vehicle.

update_state() None#

Updates the current state of the UAV.

This includes: ang_vel, ang_pos, lin_vel, lin_pos.