Data Types
AngleLevelControllerGains
Class Signature
Description
Struct to contain controller gains used by angle level PID controller.
Attributes
-
roll_gains
: kP, kI, kD for roll axis.- Type:
PIDGains
- Type:
-
pitch_gains
: kP, kI, kD for pitch axis.- Type:
PIDGains
- Type:
-
yaw_gains
: kP, kI, kD for yaw axis.- Type:
PIDGains
- Type:
Methods
to_lists()
Converts gains to list format.
AngleRateControllerGains
Class Signature
Description
Struct to contain controller gains used by angle rate PID controller.
Attributes
-
roll_gains
: kP, kI, kD for roll axis.- Type:
PIDGains
- Type:
-
pitch_gains
: kP, kI, kD for pitch axis.- Type:
PIDGains
- Type:
-
yaw_gains
: kP, kI, kD for yaw axis.- Type:
PIDGains
- Type:
Methods
to_lists()
Converts gains to list format.
BarometerData
Class Signature
Description
Barometer data for multirotor and cars in AirGen.
Default Settings
Usage Example
Attributes
-
altitude
: Altitude of the barometer.- Type: Quaternionr
-
pressure
: Pressure of the barometer.- Type: Vector3r
-
qnh
: QNH of the barometer.- Type: Vector3r
-
time_stamp
: Timestamp of the barometer data.- Type:
uint64
- Type:
Box2D
Class Signature
Description
Defines a 2D bounding box.
Attributes
Box3D
Class Signature
Description
Defines a 3D bounding box.
Attributes
CameraInfo
Class Signature
Description
Information about the camera.
Attributes
-
fov
: Field of view of the camera.- Type:
float
- Type:
-
pose
: The pose of the camera in the simulation.- Type: Pose
-
proj_mat
: Projection matrix for the camera.- Type: ProjectionMatrix
CarControls
Class Signature
Description
Controls for a car in the simulation.
Attributes
-
throttle
: Amount of throttle applied.- Type:
float
- Type:
-
steering
: Steering angle.- Type:
float
- Type:
-
brake
: Amount of braking applied.- Type:
float
- Type:
-
handbrake
: Whether the handbrake is engaged.- Type:
bool
- Type:
-
is_manual_gear
: Whether manual gear is enabled.- Type:
bool
- Type:
-
manual_gear
: Current gear in manual mode.- Type:
int
- Type:
-
gear_immediate
: Whether gear changes take immediate effect.- Type:
bool
- Type:
Methods
set_throttle(throttle_val, forward)
Sets the throttle value and direction.
CarState
Class Signature
Description
State information for a car in the simulation.
Attributes
-
collision
: Information about collisions.- Type: CollisionInfo
-
gear
: Current gear.- Type:
int
- Type:
-
handbrake
: Whether the handbrake is engaged.- Type:
bool
- Type:
-
kinematics_estimated
: Estimated kinematics of the car.- Type: KinematicsState
-
maxrpm
: Maximum revolutions per minute.- Type:
float
- Type:
-
rpm
: Current revolutions per minute.- Type:
float
- Type:
-
speed
: Current speed of the car.- Type:
float
- Type:
-
timestamp
: Timestamp of the car state.- Type:
int
- Type:
CollisionInfo
Class Signature
Description
Details about collisions in the simulation.
Attributes
-
has_collided
: Whether a collision occurred.- Type:
bool
- Type:
-
impact_point
: Location of the collision impact.- Type: Vector3r
-
impact_time
: Time of the collision.- Type:
float
- Type:
-
impact_velocity
: Velocity during impact.- Type: Vector3r
DetectionInfo
Class Signature
Description
Provides information about detected objects in the simulation.
Attributes
-
bounding_box
: The bounding box of the detected object.- Type: Box2D
-
confidence
: Confidence score of the detection.- Type:
float
- Type:
-
label
: Label of the detected object.- Type:
str
- Type:
DistanceSensorData
Class Signature
Description
Data from a distance sensor.
Attributes
-
distance
: Measured distance.- Type:
float
- Type:
-
time_stamp
: Timestamp of the data.- Type:
uint64
- Type:
DrivetrainType
Class Signature
Description
Defines the type of drivetrain for vehicles.
Attributes
value
: Specifies the drivetrain type (e.g., ForwardOnly or MaxDegreeOfFreedom).- Type:
str
- Type:
EnvironmentState
Class Signature
Description
Represents the state of the simulation environment.
Attributes
-
temperature
: Temperature in the environment.- Type:
float
- Type:
-
pressure
: Atmospheric pressure.- Type:
float
- Type:
-
humidity
: Humidity level.- Type:
float
- Type:
GeoPoint
Class Signature
Description
Represents a geographic point with latitude, longitude, and altitude.
Attributes
-
latitude
: Latitude in degrees.- Type:
float
- Type:
-
longitude
: Longitude in degrees.- Type:
float
- Type:
-
altitude
: Altitude in meters.- Type:
float
- Type:
GeoPose
Class Signature
Description
Represents a geographic pose including position and orientation.
Attributes
-
position
: Position of the object in geographic coordinates.- Type: GeoPoint
-
orientation
: Orientation of the object.- Type: Quaternionr
GnssFixType
Class Signature
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
- Type:
GnssReport
Class Signature
Description
Provides GNSS report data.
Attributes
-
geo_point
: Geographic point of the GNSS report.- Type: GeoPoint
-
gnss_fix_type
: Type of GNSS fix.- Type: GnssFixType
-
time_stamp
: Timestamp of the GNSS data.- Type:
uint64
- Type:
GpsData
Class Signature
Description
Contains GPS information.
Attributes
-
latitude
: Latitude in degrees.- Type:
float
- Type:
-
longitude
: Longitude in degrees.- Type:
float
- Type:
-
altitude
: Altitude in meters.- Type:
float
- Type:
-
time_stamp
: Time when the data was recorded.- Type:
uint64
- Type:
ImageRequest
Class Signature
Description
Represents a request for capturing an image in the simulation.
Attributes
-
camera_name
: Name of the camera to capture the image.- Type:
str
- Type:
-
image_type
: Type of image to capture (e.g., Scene, Depth, or Segmentation).- Type: ImageType
-
pixels_as_float
: Whether the image pixels should be returned as floats.- Type:
bool
- Type:
-
compress
: Whether the image should be compressed.- Type:
bool
- Type:
GPSData
Class Signature
Description
Contains GPS information.
Attributes
-
latitude
: Latitude in degrees.- Type:
float
- Type:
-
longitude
: Longitude in degrees.- Type:
float
- Type:
-
altitude
: Altitude in meters.- Type:
float
- Type:
-
time_stamp
: Time when the data was recorded.- Type:
uint64
- Type:
IMUData
Class Signature
Description
IMU (Inertial Measurement Unit) data including accelerometer and gyroscope readings.
Attributes
-
linear_acceleration
: Linear acceleration vector.- Type: Vector3r
-
angular_velocity
: Angular velocity vector.- Type: Vector3r
-
time_stamp
: Timestamp of the IMU data.- Type:
uint64
- Type:
MagnetometerData
Class Signature
Description
Provides data from a magnetometer sensor.
Attributes
-
magnetic_field_body
: Magnetic field vector in the body frame.- Type: Vector3r
-
time_stamp
: Timestamp of the magnetometer data.- Type:
uint64
- Type:
LidarData
Class Signature
Description
Contains data from a LiDAR sensor.
Attributes
-
point_cloud
: The point cloud data captured by the LiDAR.- Type:
list[float]
- Type:
-
time_stamp
: Timestamp of the LiDAR data.- Type:
uint64
- Type:
-
pose
: Pose of the LiDAR in the simulation.- Type: Pose
CameraCaptureInfo
Class Signature
Description
Provides metadata for a camera capture.
Attributes
-
time_stamp
: Time when the image was captured.- Type:
uint64
- Type:
-
pose
: Pose of the camera at the time of capture.- Type: Pose
-
projection_matrix
: Projection matrix of the camera.- Type: ProjectionMatrix
ImageResponse
Class Signature
Description
Represents a response containing image data captured in the simulation.
Attributes
-
image_data_uint8
: Image data in uint8 format.- Type:
list[uint8]
- Type:
-
image_data_float
: Image data in float format.- Type:
list[float]
- Type:
-
time_stamp
: Timestamp of the captured image.- Type:
uint64
- Type:
-
width
: Width of the image in pixels.- Type:
int
- Type:
-
height
: Height of the image in pixels.- Type:
int
- Type:
-
image_type
: Type of the captured image.- Type: ImageType
ImageType
Class Signature
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
- Type:
ImuData
Class Signature
Description
Provides data from the Inertial Measurement Unit (IMU) sensor.
Attributes
-
linear_acceleration
: Linear acceleration vector.- Type: Vector3r
-
angular_velocity
: Angular velocity vector.- Type: Vector3r
-
time_stamp
: Timestamp of the IMU data.- Type:
uint64
- Type:
KinematicsState
Class Signature
Description
Represents the kinematic state of an object in the simulation.
Attributes
-
position
: Position vector.- Type: Vector3r
-
orientation
: Orientation quaternion.- Type: Quaternionr
-
linear_velocity
: Linear velocity vector.- Type: Vector3r
-
angular_velocity
: Angular velocity vector.- Type: Vector3r
-
linear_acceleration
: Linear acceleration vector.- Type: Vector3r
-
angular_acceleration
: Angular acceleration vector.- Type: Vector3r
LandedState
Class Signature
Description
Defines the landing state of a multirotor vehicle.
Attributes
state
: The landed state (e.g., Landed, Flying, or Unknown).- Type:
str
- Type:
LidarData
Class Signature
Description
Contains data from a LiDAR sensor.
Attributes
-
point_cloud
: The point cloud data captured by the LiDAR.- Type:
list[float]
- Type:
-
time_stamp
: Timestamp of the LiDAR data.- Type:
uint64
- Type:
-
pose
: Pose of the LiDAR in the simulation.- Type: Pose
MagnetometerData
Class Signature
Description
Provides data from a magnetometer sensor.
Attributes
-
magnetic_field_body
: Magnetic field vector in the body frame.- Type: Vector3r
-
time_stamp
: Timestamp of the magnetometer data.- Type:
uint64
- Type:
MeshPositionVertexBuffers
Class Signature
Description
Represents vertex buffers for mesh positions.
Attributes
-
vertex_positions
: List of vertex positions.- Type:
list[[Vector3r](/simulation/airgen/reference/datatypes#vector3r)]
- Type:
-
vertex_normals
: List of vertex normals.- Type:
list[[Vector3r](/simulation/airgen/reference/datatypes#vector3r)]
- Type:
-
indices
: List of indices for the mesh.- Type:
list[int]
- Type:
MsgackMixin
Class Signature
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
Description
Defines the state of a multirotor vehicle.
Attributes
-
kinematics_estimated
: Estimated kinematic state of the multirotor.- Type: KinematicsState
-
gps_data
: GPS data of the multirotor.- Type: GpsData
-
imu_data
: IMU data of the multirotor.- Type: ImuData
-
magnetometer_data
: Magnetometer data of the multirotor.- Type: MagnetometerData
-
lidar_data
: LiDAR data of the multirotor.- Type: LidarData
-
landed_state
: Landed state of the multirotor.- Type: `LandedState
PIDGains
Class Signature
Description
Defines the PID controller gains.
Attributes
-
kP
: Proportional gain.- Type:
float
- Type:
-
kI
: Integral gain.- Type:
float
- Type:
-
kD
: Derivative gain.- Type:
float
- Type:
Pose
Class Signature
Description
Represents the pose of an object, including position and orientation.
Attributes
-
position
: Position vector.- Type: Vector3r
-
orientation
: Orientation quaternion.- Type: Quaternionr
PositionControllerGains
Class Signature
Description
Defines the gains for position control.
Attributes
-
x_gains
: PID gains for the x-axis.- Type:
PIDGains
- Type:
-
y_gains
: PID gains for the y-axis.- Type:
PIDGains
- Type:
-
z_gains
: PID gains for the z-axis.- Type:
PIDGains
- Type:
ProjectionMatrix
Class Signature
Description
Represents a 4x4 projection matrix for 3D graphics.
Attributes
matrix
: 4x4 matrix values stored in row-major order.- Type:
list[float]
- Type:
Quaternionr
Class Signature
Description
Represents a quaternion for 3D rotations.
Attributes
-
x
: x component of the quaternion.- Type:
float
- Type:
-
y
: y component of the quaternion.- Type:
float
- Type:
-
z
: z component of the quaternion.- Type:
float
- Type:
-
w
: w component (scalar) of the quaternion.- Type:
float
- Type:
RCData
Class Signature
Description
Represents data from a remote control (RC) device.
Attributes
-
is_valid
: Whether the RC data is valid.- Type:
bool
- Type:
-
throttle
: Throttle value from the RC.- Type:
float
- Type:
-
yaw
: Yaw value from the RC.- Type:
float
- Type:
-
roll
: Roll value from the RC.- Type:
float
- Type:
-
pitch
: Pitch value from the RC.- Type:
float
- Type:
RotorStates
Class Signature
Description
Represents the state of all rotors in a multirotor vehicle.
Attributes
-
rotor_speeds
: List of rotor speeds.- Type:
list[float]
- Type:
-
rotor_thrusts
: List of rotor thrusts.- Type:
list[float]
- Type:
-
rotor_controls
: List of rotor controls.- Type:
list[float]
- Type:
Vector2r
Class Signature
Description
Represents a 2D vector.
Attributes
-
x
: x component of the vector.- Type:
float
- Type:
-
y
: y component of the vector.- Type:
float
- Type:
Vector3r
Class Signature
Description
Represents a 3D vector.
Attributes
-
x
: x component of the vector.- Type:
float
- Type:
-
y
: y component of the vector.- Type:
float
- Type:
-
z
: z component of the vector.- Type:
float
- Type:
VelocityControllerGains
Class Signature
Description
Defines the gains for velocity control.
Attributes
-
linear_gains
: PID gains for linear velocity.- Type:
PIDGains
- Type:
-
angular_gains
: PID gains for angular velocity.- Type:
PIDGains
- Type:
WeatherParameter
Class Signature
Description
Represents a parameter for weather simulation.
Attributes
-
parameter_name
: Name of the weather parameter (e.g., “Rain”, “WindSpeed”).- Type:
str
- Type:
-
value
: Value of the parameter.- Type:
float
- Type:
YawMode
Class Signature
Description
Defines the yaw control mode.
Attributes
-
is_rate
: Indicates whether yaw represents a rate (degrees/second) or an absolute angle.- Type:
bool
- Type:
-
yaw_or_rate
: Yaw value, which can be either a rate or an angle depending onis_rate
.- Type:
float
- Type:
Was this page helpful?