AngleLevelControllerGains

Class Signature

class airgen.types.AngleLevelControllerGains(
    roll_gains=<airgen.types.PIDGains object>,
    pitch_gains=<airgen.types.PIDGains object>,
    yaw_gains=<airgen.types.PIDGains object>
)

Description

Struct to contain controller gains used by angle level PID controller.

Attributes

  • roll_gains: kP, kI, kD for roll axis.

    • Type: PIDGains
  • pitch_gains: kP, kI, kD for pitch axis.

    • Type: PIDGains
  • yaw_gains: kP, kI, kD for yaw axis.

    • Type: PIDGains

Methods

  • to_lists() Converts gains to list format.

AngleRateControllerGains

Class Signature

class airgen.types.AngleRateControllerGains(
    roll_gains=<airgen.types.PIDGains object>,
    pitch_gains=<airgen.types.PIDGains object>,
    yaw_gains=<airgen.types.PIDGains object>
)

Description

Struct to contain controller gains used by angle rate PID controller.

Attributes

  • roll_gains: kP, kI, kD for roll axis.

    • Type: PIDGains
  • pitch_gains: kP, kI, kD for pitch axis.

    • Type: PIDGains
  • yaw_gains: kP, kI, kD for yaw axis.

    • Type: PIDGains

Methods

  • to_lists() Converts gains to list format.

BarometerData

Class Signature

class airgen.types.BarometerData

Description

Barometer data for multirotor and cars in AirGen.

Default Settings

{
  "DefaultSensors": {
    "BarometerSensorName": {
      "SensorType": 1,
      "Enabled": true,
      "PressureFactorSigma": 0.001825,
      "PressureFactorTau": 3600,
      "UncorrelatedNoiseSigma": 2.7,
      "UpdateLatency": 0,
      "UpdateFrequency": 50,
      "StartupDelay": 0
    }
  }
}

Usage Example

barometer_data = airgen_client.getBarometerData("BarometerSensorName")

Attributes

  • altitude: Altitude of the barometer.

  • pressure: Pressure of the barometer.

  • qnh: QNH of the barometer.

  • time_stamp: Timestamp of the barometer data.

    • Type: uint64

Box2D

Class Signature

class airgen.types.Box2D

Description

Defines a 2D bounding box.

Attributes

  • max: Maximum coordinates.

  • min: Minimum coordinates.

Box3D

Class Signature

class airgen.types.Box3D

Description

Defines a 3D bounding box.

Attributes

  • max: Maximum coordinates.

  • min: Minimum coordinates.

CameraInfo

Class Signature

class airgen.types.CameraInfo

Description

Information about the camera.

Attributes

  • fov: Field of view of the camera.

    • Type: float
  • pose: The pose of the camera in the simulation.

  • proj_mat: Projection matrix for the camera.

CarControls

Class Signature

class airgen.types.CarControls(
    throttle=0,
    steering=0,
    brake=0,
    handbrake=False,
    is_manual_gear=False,
    manual_gear=0,
    gear_immediate=True
)

Description

Controls for a car in the simulation.

Attributes

  • throttle: Amount of throttle applied.

    • Type: float
  • steering: Steering angle.

    • Type: float
  • brake: Amount of braking applied.

    • Type: float
  • handbrake: Whether the handbrake is engaged.

    • Type: bool
  • is_manual_gear: Whether manual gear is enabled.

    • Type: bool
  • manual_gear: Current gear in manual mode.

    • Type: int
  • gear_immediate: Whether gear changes take immediate effect.

    • Type: bool

Methods

  • set_throttle(throttle_val, forward) Sets the throttle value and direction.

CarState

Class Signature

class airgen.types.CarState

Description

State information for a car in the simulation.

Attributes

  • collision: Information about collisions.

  • gear: Current gear.

    • Type: int
  • handbrake: Whether the handbrake is engaged.

    • Type: bool
  • kinematics_estimated: Estimated kinematics of the car.

  • maxrpm: Maximum revolutions per minute.

    • Type: float
  • rpm: Current revolutions per minute.

    • Type: float
  • speed: Current speed of the car.

    • Type: float
  • timestamp: Timestamp of the car state.

    • Type: int

CollisionInfo

Class Signature

class airgen.types.CollisionInfo

Description

Details about collisions in the simulation.

Attributes

  • has_collided: Whether a collision occurred.

    • Type: bool
  • impact_point: Location of the collision impact.

  • impact_time: Time of the collision.

    • Type: float
  • impact_velocity: Velocity during impact.

DetectionInfo

Class Signature

class airgen.types.DetectionInfo

Description

Provides information about detected objects in the simulation.

Attributes

  • bounding_box: The bounding box of the detected object.

  • confidence: Confidence score of the detection.

    • Type: float
  • label: Label of the detected object.

    • Type: str

DistanceSensorData

Class Signature

class airgen.types.DistanceSensorData

Description

Data from a distance sensor.

Attributes

  • distance: Measured distance.

    • Type: float
  • time_stamp: Timestamp of the data.

    • Type: uint64

DrivetrainType

Class Signature

class airgen.types.DrivetrainType

Description

Defines the type of drivetrain for vehicles.

Attributes

  • value: Specifies the drivetrain type (e.g., ForwardOnly or MaxDegreeOfFreedom).
    • Type: str

EnvironmentState

Class Signature

class airgen.types.EnvironmentState

Description

Represents the state of the simulation environment.

Attributes

  • temperature: Temperature in the environment.

    • Type: float
  • pressure: Atmospheric pressure.

    • Type: float
  • humidity: Humidity level.

    • Type: float

GeoPoint

Class Signature

class airgen.types.GeoPoint

Description

Represents a geographic point with latitude, longitude, and altitude.

Attributes

  • latitude: Latitude in degrees.

    • Type: float
  • longitude: Longitude in degrees.

    • Type: float
  • altitude: Altitude in meters.

    • Type: float

GeoPose

Class Signature

class airgen.types.GeoPose

Description

Represents a geographic pose including position and orientation.

Attributes

  • position: Position of the object in geographic coordinates.

  • orientation: Orientation of the object.

GnssFixType

Class Signature

class airgen.types.GnssFixType

Description

Defines the type of GNSS (Global Navigation Satellite System) fix.

Attributes

  • fix_type: Type of GNSS fix (e.g., NoFix, TimeOnly, or PositionFix).
    • Type: str

GnssReport

Class Signature

class airgen.types.GnssReport

Description

Provides GNSS report data.

Attributes

  • geo_point: Geographic point of the GNSS report.

  • gnss_fix_type: Type of GNSS fix.

  • time_stamp: Timestamp of the GNSS data.

    • Type: uint64

GpsData

Class Signature

class airgen.types.GpsData

Description

Contains GPS information.

Attributes

  • latitude: Latitude in degrees.

    • Type: float
  • longitude: Longitude in degrees.

    • Type: float
  • altitude: Altitude in meters.

    • Type: float
  • time_stamp: Time when the data was recorded.

    • Type: uint64

ImageRequest

Class Signature

class airgen.types.ImageRequest

Description

Represents a request for capturing an image in the simulation.

Attributes

  • camera_name: Name of the camera to capture the image.

    • Type: str
  • image_type: Type of image to capture (e.g., Scene, Depth, or Segmentation).

  • pixels_as_float: Whether the image pixels should be returned as floats.

    • Type: bool
  • compress: Whether the image should be compressed.

    • Type: bool

GPSData

Class Signature

class airgen.types.GPSData

Description

Contains GPS information.

Attributes

  • latitude: Latitude in degrees.

    • Type: float
  • longitude: Longitude in degrees.

    • Type: float
  • altitude: Altitude in meters.

    • Type: float
  • time_stamp: Time when the data was recorded.

    • Type: uint64

IMUData

Class Signature

class airgen.types.IMUData

Description

IMU (Inertial Measurement Unit) data including accelerometer and gyroscope readings.

Attributes

  • linear_acceleration: Linear acceleration vector.

  • angular_velocity: Angular velocity vector.

  • time_stamp: Timestamp of the IMU data.

    • Type: uint64

MagnetometerData

Class Signature

class airgen.types.MagnetometerData

Description

Provides data from a magnetometer sensor.

Attributes

  • magnetic_field_body: Magnetic field vector in the body frame.

  • time_stamp: Timestamp of the magnetometer data.

    • Type: uint64

LidarData

Class Signature

class airgen.types.LidarData

Description

Contains data from a LiDAR sensor.

Attributes

  • point_cloud: The point cloud data captured by the LiDAR.

    • Type: list[float]
  • time_stamp: Timestamp of the LiDAR data.

    • Type: uint64
  • pose: Pose of the LiDAR in the simulation.

CameraCaptureInfo

Class Signature

class airgen.types.CameraCaptureInfo

Description

Provides metadata for a camera capture.

Attributes

  • time_stamp: Time when the image was captured.

    • Type: uint64
  • pose: Pose of the camera at the time of capture.

  • projection_matrix: Projection matrix of the camera.

ImageResponse

Class Signature

class airgen.types.ImageResponse

Description

Represents a response containing image data captured in the simulation.

Attributes

  • image_data_uint8: Image data in uint8 format.

    • Type: list[uint8]
  • image_data_float: Image data in float format.

    • Type: list[float]
  • time_stamp: Timestamp of the captured image.

    • Type: uint64
  • width: Width of the image in pixels.

    • Type: int
  • height: Height of the image in pixels.

    • Type: int
  • image_type: Type of the captured image.

ImageType

Class Signature

class airgen.types.ImageType

Description

Defines the type of images that can be captured in the simulation.

Attributes

  • type: The image type (e.g., Scene, Depth, or Segmentation).
    • Type: str

ImuData

Class Signature

class airgen.types.ImuData

Description

Provides data from the Inertial Measurement Unit (IMU) sensor.

Attributes

  • linear_acceleration: Linear acceleration vector.

  • angular_velocity: Angular velocity vector.

  • time_stamp: Timestamp of the IMU data.

    • Type: uint64

KinematicsState

Class Signature

class airgen.types.KinematicsState

Description

Represents the kinematic state of an object in the simulation.

Attributes

  • position: Position vector.

  • orientation: Orientation quaternion.

  • linear_velocity: Linear velocity vector.

  • angular_velocity: Angular velocity vector.

  • linear_acceleration: Linear acceleration vector.

  • angular_acceleration: Angular acceleration vector.

LandedState

Class Signature

class airgen.types.LandedState

Description

Defines the landing state of a multirotor vehicle.

Attributes

  • state: The landed state (e.g., Landed, Flying, or Unknown).
    • Type: str

LidarData

Class Signature

class airgen.types.LidarData

Description

Contains data from a LiDAR sensor.

Attributes

  • point_cloud: The point cloud data captured by the LiDAR.

    • Type: list[float]
  • time_stamp: Timestamp of the LiDAR data.

    • Type: uint64
  • pose: Pose of the LiDAR in the simulation.

MagnetometerData

Class Signature

class airgen.types.MagnetometerData

Description

Provides data from a magnetometer sensor.

Attributes

  • magnetic_field_body: Magnetic field vector in the body frame.

  • time_stamp: Timestamp of the magnetometer data.

    • Type: uint64

MeshPositionVertexBuffers

Class Signature

class airgen.types.MeshPositionVertexBuffers

Description

Represents vertex buffers for mesh positions.

Attributes

  • vertex_positions: List of vertex positions.

    • Type: list[[Vector3r](/simulation/airgen/reference/datatypes#vector3r)]
  • vertex_normals: List of vertex normals.

    • Type: list[[Vector3r](/simulation/airgen/reference/datatypes#vector3r)]
  • indices: List of indices for the mesh.

    • Type: list[int]

MsgackMixin

Class Signature

class airgen.types.MsgackMixin

Description

Mixin class for enabling message serialization and deserialization.

Methods

  • to_msgpack(): Serializes the object to msgpack format.

  • from_msgpack(): Deserializes the object from msgpack format.

MultirotorState

Class Signature

class airgen.types.MultirotorState

Description

Defines the state of a multirotor vehicle.

Attributes

  • kinematics_estimated: Estimated kinematic state of the multirotor.

  • gps_data: GPS data of the multirotor.

  • imu_data: IMU data of the multirotor.

  • magnetometer_data: Magnetometer data of the multirotor.

  • lidar_data: LiDAR data of the multirotor.

  • landed_state: Landed state of the multirotor.

    • Type: `LandedState

    PIDGains

Class Signature

class airgen.types.PIDGains

Description

Defines the PID controller gains.

Attributes

  • kP: Proportional gain.

    • Type: float
  • kI: Integral gain.

    • Type: float
  • kD: Derivative gain.

    • Type: float

Pose

Class Signature

class airgen.types.Pose

Description

Represents the pose of an object, including position and orientation.

Attributes

  • position: Position vector.

  • orientation: Orientation quaternion.

PositionControllerGains

Class Signature

class airgen.types.PositionControllerGains

Description

Defines the gains for position control.

Attributes

  • x_gains: PID gains for the x-axis.

    • Type: PIDGains
  • y_gains: PID gains for the y-axis.

    • Type: PIDGains
  • z_gains: PID gains for the z-axis.

    • Type: PIDGains

ProjectionMatrix

Class Signature

class airgen.types.ProjectionMatrix

Description

Represents a 4x4 projection matrix for 3D graphics.

Attributes

  • matrix: 4x4 matrix values stored in row-major order.
    • Type: list[float]

Quaternionr

Class Signature

class airgen.types.Quaternionr

Description

Represents a quaternion for 3D rotations.

Attributes

  • x: x component of the quaternion.

    • Type: float
  • y: y component of the quaternion.

    • Type: float
  • z: z component of the quaternion.

    • Type: float
  • w: w component (scalar) of the quaternion.

    • Type: float

RCData

Class Signature

class airgen.types.RCData

Description

Represents data from a remote control (RC) device.

Attributes

  • is_valid: Whether the RC data is valid.

    • Type: bool
  • throttle: Throttle value from the RC.

    • Type: float
  • yaw: Yaw value from the RC.

    • Type: float
  • roll: Roll value from the RC.

    • Type: float
  • pitch: Pitch value from the RC.

    • Type: float

RotorStates

Class Signature

class airgen.types.RotorStates

Description

Represents the state of all rotors in a multirotor vehicle.

Attributes

  • rotor_speeds: List of rotor speeds.

    • Type: list[float]
  • rotor_thrusts: List of rotor thrusts.

    • Type: list[float]
  • rotor_controls: List of rotor controls.

    • Type: list[float]

Vector2r

Class Signature

class airgen.types.Vector2r

Description

Represents a 2D vector.

Attributes

  • x: x component of the vector.

    • Type: float
  • y: y component of the vector.

    • Type: float

Vector3r

Class Signature

class airgen.types.Vector3r

Description

Represents a 3D vector.

Attributes

  • x: x component of the vector.

    • Type: float
  • y: y component of the vector.

    • Type: float
  • z: z component of the vector.

    • Type: float

VelocityControllerGains

Class Signature

class airgen.types.VelocityControllerGains

Description

Defines the gains for velocity control.

Attributes

  • linear_gains: PID gains for linear velocity.

    • Type: PIDGains
  • angular_gains: PID gains for angular velocity.

    • Type: PIDGains

WeatherParameter

Class Signature

class airgen.types.WeatherParameter

Description

Represents a parameter for weather simulation.

Attributes

  • parameter_name: Name of the weather parameter (e.g., “Rain”, “WindSpeed”).

    • Type: str
  • value: Value of the parameter.

    • Type: float

YawMode

Class Signature

class airgen.types.YawMode

Description

Defines the yaw control mode.

Attributes

  • is_rate: Indicates whether yaw represents a rate (degrees/second) or an absolute angle.

    • Type: bool
  • yaw_or_rate: Yaw value, which can be either a rate or an angle depending on is_rate.

    • Type: float

Was this page helpful?