Fixedwing#

Model Description#

Small tube-and-wing fixed wing UAV with a single motor (~2.5 Kg).

Variants#

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

  • fixedwing (default)

  • acrowing

    • A more aggressive aircraft with higher thrust:weight ratio, bigger flight and control surfaces, and a trailing edge flap.

Control Mode#

Two modes are available and documented below.

Class Description#

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

Fixedwing instance that handles everything about a FixedWing.

reset() None#

Resets the vehicle to the initial state.

set_mode(mode) None#

Sets the current flight mode of the vehicle.

flight modes:
  • -1: Left Aileron, Right Aileron, Horizontal Tail, Vertical Tail, Main Wing, Thrust

  • 0: Pitch, Roll, Yaw, Thrust

Parameters:

mode (int) – flight mode

starting_velocity#

Reads fixedwing.yaml file and load UAV parameters

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.