├── .github ├── dependabot.yml └── workflows │ └── build.yml ├── .gitignore ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── README.md ├── msg ├── ActionRequest.msg ├── ActuatorArmed.msg ├── ActuatorControlsStatus.msg ├── ActuatorMotors.msg ├── ActuatorOutputs.msg ├── ActuatorServos.msg ├── ActuatorServosTrim.msg ├── ActuatorTest.msg ├── AdcReport.msg ├── Airspeed.msg ├── AirspeedValidated.msg ├── AirspeedWind.msg ├── ArmingCheckReply.msg ├── ArmingCheckRequest.msg ├── AutotuneAttitudeControlStatus.msg ├── BatteryStatus.msg ├── ButtonEvent.msg ├── CameraCapture.msg ├── CameraStatus.msg ├── CameraTrigger.msg ├── CanInterfaceStatus.msg ├── CellularStatus.msg ├── CollisionConstraints.msg ├── ConfigOverrides.msg ├── ControlAllocatorStatus.msg ├── Cpuload.msg ├── DatamanRequest.msg ├── DatamanResponse.msg ├── DebugArray.msg ├── DebugKeyValue.msg ├── DebugValue.msg ├── DebugVect.msg ├── DifferentialPressure.msg ├── DistanceSensor.msg ├── DistanceSensorModeChangeRequest.msg ├── Ekf2Timestamps.msg ├── EscReport.msg ├── EscStatus.msg ├── EstimatorAidSource1d.msg ├── EstimatorAidSource2d.msg ├── EstimatorAidSource3d.msg ├── EstimatorBias.msg ├── EstimatorBias3d.msg ├── EstimatorEventFlags.msg ├── EstimatorGpsStatus.msg ├── EstimatorInnovations.msg ├── EstimatorSelectorStatus.msg ├── EstimatorSensorBias.msg ├── EstimatorStates.msg ├── EstimatorStatus.msg ├── EstimatorStatusFlags.msg ├── Event.msg ├── FailsafeFlags.msg ├── FailureDetectorStatus.msg ├── FigureEightStatus.msg ├── FixedWingLateralGuidanceStatus.msg ├── FixedWingLateralSetpoint.msg ├── FixedWingLateralStatus.msg ├── FixedWingLongitudinalSetpoint.msg ├── FixedWingRunwayControl.msg ├── FlightPhaseEstimation.msg ├── FollowTarget.msg ├── FollowTargetEstimator.msg ├── FollowTargetStatus.msg ├── FuelTankStatus.msg ├── GeneratorStatus.msg ├── GeofenceResult.msg ├── GeofenceStatus.msg ├── GimbalControls.msg ├── GimbalDeviceAttitudeStatus.msg ├── GimbalDeviceInformation.msg ├── GimbalDeviceSetAttitude.msg ├── GimbalManagerInformation.msg ├── GimbalManagerSetAttitude.msg ├── GimbalManagerSetManualControl.msg ├── GimbalManagerStatus.msg ├── GotoSetpoint.msg ├── GpioConfig.msg ├── GpioIn.msg ├── GpioOut.msg ├── GpioRequest.msg ├── GpsDump.msg ├── GpsInjectData.msg ├── Gripper.msg ├── HealthReport.msg ├── HeaterStatus.msg ├── HomePosition.msg ├── HoverThrustEstimate.msg ├── InputRc.msg ├── InternalCombustionEngineControl.msg ├── InternalCombustionEngineStatus.msg ├── IridiumsbdStatus.msg ├── IrlockReport.msg ├── LandingGear.msg ├── LandingGearWheel.msg ├── LandingTargetInnovations.msg ├── LandingTargetPose.msg ├── LateralControlConfiguration.msg ├── LaunchDetectionStatus.msg ├── LedControl.msg ├── LogMessage.msg ├── LoggerStatus.msg ├── LongitudinalControlConfiguration.msg ├── MagWorkerData.msg ├── MagnetometerBiasEstimate.msg ├── ManualControlSetpoint.msg ├── ManualControlSwitches.msg ├── MavlinkLog.msg ├── MavlinkTunnel.msg ├── MessageFormatRequest.msg ├── MessageFormatResponse.msg ├── Mission.msg ├── MissionResult.msg ├── ModeCompleted.msg ├── MountOrientation.msg ├── NavigatorMissionItem.msg ├── NavigatorStatus.msg ├── NormalizedUnsignedSetpoint.msg ├── ObstacleDistance.msg ├── OffboardControlMode.msg ├── OnboardComputerStatus.msg ├── OpenDroneIdArmStatus.msg ├── OpenDroneIdOperatorId.msg ├── OpenDroneIdSelfId.msg ├── OpenDroneIdSystem.msg ├── OrbTest.msg ├── OrbTestLarge.msg ├── OrbTestMedium.msg ├── OrbitStatus.msg ├── ParameterResetRequest.msg ├── ParameterSetUsedRequest.msg ├── ParameterSetValueRequest.msg ├── ParameterSetValueResponse.msg ├── ParameterUpdate.msg ├── Ping.msg ├── PositionControllerLandingStatus.msg ├── PositionControllerStatus.msg ├── PositionSetpoint.msg ├── PositionSetpointTriplet.msg ├── PowerButtonState.msg ├── PowerMonitor.msg ├── PpsCapture.msg ├── PurePursuitStatus.msg ├── PwmInput.msg ├── Px4ioStatus.msg ├── QshellReq.msg ├── QshellRetval.msg ├── RadioStatus.msg ├── RateCtrlStatus.msg ├── RcChannels.msg ├── RcParameterMap.msg ├── RegisterExtComponentReply.msg ├── RegisterExtComponentRequest.msg ├── RoverAttitudeSetpoint.msg ├── RoverAttitudeStatus.msg ├── RoverPositionSetpoint.msg ├── RoverRateSetpoint.msg ├── RoverRateStatus.msg ├── RoverSteeringSetpoint.msg ├── RoverThrottleSetpoint.msg ├── RoverVelocitySetpoint.msg ├── RoverVelocityStatus.msg ├── Rpm.msg ├── RtlStatus.msg ├── RtlTimeEstimate.msg ├── SatelliteInfo.msg ├── SensorAccel.msg ├── SensorAccelFifo.msg ├── SensorAirflow.msg ├── SensorBaro.msg ├── SensorCombined.msg ├── SensorCorrection.msg ├── SensorGnssRelative.msg ├── SensorGps.msg ├── SensorGyro.msg ├── SensorGyroFft.msg ├── SensorGyroFifo.msg ├── SensorHygrometer.msg ├── SensorMag.msg ├── SensorOpticalFlow.msg ├── SensorPreflightMag.msg ├── SensorSelection.msg ├── SensorUwb.msg ├── SensorsStatus.msg ├── SensorsStatusImu.msg ├── SystemPower.msg ├── TakeoffStatus.msg ├── TaskStackInfo.msg ├── TecsStatus.msg ├── TelemetryStatus.msg ├── TiltrotorExtraControls.msg ├── TimesyncStatus.msg ├── TrajectorySetpoint.msg ├── TrajectorySetpoint6dof.msg ├── TransponderReport.msg ├── TuneControl.msg ├── UavcanParameterRequest.msg ├── UavcanParameterValue.msg ├── UlogStream.msg ├── UlogStreamAck.msg ├── UnregisterExtComponent.msg ├── VehicleAcceleration.msg ├── VehicleAirData.msg ├── VehicleAngularAccelerationSetpoint.msg ├── VehicleAngularVelocity.msg ├── VehicleAttitude.msg ├── VehicleAttitudeSetpoint.msg ├── VehicleCommand.msg ├── VehicleCommandAck.msg ├── VehicleConstraints.msg ├── VehicleControlMode.msg ├── VehicleGlobalPosition.msg ├── VehicleImu.msg ├── VehicleImuStatus.msg ├── VehicleLandDetected.msg ├── VehicleLocalPosition.msg ├── VehicleLocalPositionSetpoint.msg ├── VehicleMagnetometer.msg ├── VehicleOdometry.msg ├── VehicleOpticalFlow.msg ├── VehicleOpticalFlowVel.msg ├── VehicleRatesSetpoint.msg ├── VehicleRoi.msg ├── VehicleStatus.msg ├── VehicleThrustSetpoint.msg ├── VehicleTorqueSetpoint.msg ├── VelocityLimits.msg ├── VtolVehicleStatus.msg ├── WheelEncoders.msg ├── Wind.msg └── YawEstimatorStatus.msg ├── package.xml └── srv └── VehicleCommand.srv /.github/dependabot.yml: -------------------------------------------------------------------------------- 1 | version: 2 2 | updates: 3 | - package-ecosystem: github-actions 4 | directory: "/" 5 | schedule: 6 | interval: "daily" 7 | -------------------------------------------------------------------------------- /.github/workflows/build.yml: -------------------------------------------------------------------------------- 1 | name: Build package 2 | 3 | # CI runs over all branches that do not contain 'ros1' in the name 4 | on: 5 | push: 6 | schedule: 7 | - cron: '0 0 * * *' 8 | 9 | defaults: 10 | run: 11 | shell: bash 12 | 13 | jobs: 14 | focal: 15 | name: "Build on Ubuntu Focal" 16 | runs-on: ubuntu-20.04 17 | steps: 18 | - uses: actions/checkout@v4 19 | - uses: ros-tooling/setup-ros@v0.6 20 | with: 21 | required-ros-distributions: foxy 22 | - uses: ros-tooling/action-ros-ci@v0.3 23 | with: 24 | package-name: px4_msgs 25 | target-ros2-distro: foxy 26 | jammy: 27 | name: "Build on Ubuntu Jammy" 28 | runs-on: ubuntu-22.04 29 | strategy: 30 | matrix: 31 | ros2_distro: [humble, rolling] 32 | steps: 33 | - uses: actions/checkout@v4 34 | - uses: ros-tooling/setup-ros@v0.6 35 | with: 36 | required-ros-distributions: ${{ matrix.ros2_distro }} 37 | - uses: ros-tooling/action-ros-ci@v0.3 38 | with: 39 | package-name: px4_msgs 40 | target-ros2-distro: ${{ matrix.ros2_distro }} -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | build/ 2 | msg/idl.cc 3 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(px4_msgs) 4 | 5 | list(INSERT CMAKE_MODULE_PATH 0 "${CMAKE_CURRENT_SOURCE_DIR}/cmake") 6 | 7 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 8 | add_compile_options(-Wall -Wextra) 9 | endif() 10 | 11 | find_package(ament_cmake REQUIRED) 12 | find_package(builtin_interfaces REQUIRED) 13 | find_package(rosidl_default_generators REQUIRED) 14 | 15 | # ############################################################################## 16 | # Generate ROS messages, ROS2 interfaces and IDL files # 17 | # ############################################################################## 18 | 19 | # get all msg files 20 | set(MSGS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/msg") 21 | file(GLOB PX4_MSGS RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" "${MSGS_DIR}/*.msg") 22 | 23 | # get all srv files 24 | set(SRVS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/srv") 25 | file(GLOB PX4_SRVS RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" "${SRVS_DIR}/*.srv") 26 | 27 | # Generate introspection typesupport for C and C++ and IDL files 28 | rosidl_generate_interfaces(${PROJECT_NAME} 29 | ${PX4_MSGS} 30 | ${PX4_SRVS} 31 | DEPENDENCIES builtin_interfaces 32 | ADD_LINTER_TESTS 33 | ) 34 | 35 | ament_export_dependencies(rosidl_default_runtime) 36 | 37 | ament_package() 38 | -------------------------------------------------------------------------------- /CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | # Contributing 2 | 3 | *Do not* commit changes directly to this repository that change the message definitions. All the message definitions are directly generated from the [uORB msg definitions](https://github.com/PX4/Firmware/tree/master/msg) on the [PX4 Firmware repository](https://github.com/PX4/Firmware). Any fixes or improvements one finds suitable to apply to the message definitions should be directly done on the uORB message files. The deployment of these are taken care by a Jenkins CI/CD stage. 4 | 5 | ### Contributing to the PX4 Firmware repository (or to this repository, not including message definitions) 6 | 7 | Follow the [`Contributing` guide](https://github.com/PX4/Firmware/blob/master/CONTRIBUTING.md) from the PX4 Firmware repo. 8 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2019, PX4 Development Team 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | * Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | * Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | * Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /msg/ActionRequest.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 action # what action is requested 4 | uint8 ACTION_DISARM = 0 5 | uint8 ACTION_ARM = 1 6 | uint8 ACTION_TOGGLE_ARMING = 2 7 | uint8 ACTION_UNKILL = 3 8 | uint8 ACTION_KILL = 4 9 | uint8 ACTION_SWITCH_MODE = 5 10 | uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 11 | uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 12 | 13 | uint8 source # how the request was triggered 14 | uint8 SOURCE_STICK_GESTURE = 0 15 | uint8 SOURCE_RC_SWITCH = 1 16 | uint8 SOURCE_RC_BUTTON = 2 17 | uint8 SOURCE_RC_MODE_SLOT = 3 18 | 19 | uint8 mode # for ACTION_SWITCH_MODE what mode is requested according to vehicle_status_s::NAVIGATION_STATE_* 20 | -------------------------------------------------------------------------------- /msg/ActuatorArmed.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | bool armed # Set to true if system is armed 4 | bool prearmed # Set to true if the actuator safety is disabled but motors are not armed 5 | bool ready_to_arm # Set to true if system is ready to be armed 6 | bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL) 7 | bool manual_lockdown # Set to true if manual throttle kill switch is engaged 8 | bool force_failsafe # Set to true if the actuators are forced to the failsafe position 9 | bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics 10 | -------------------------------------------------------------------------------- /msg/ActuatorControlsStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32[3] control_power 4 | 5 | # TOPICS actuator_controls_status_0 actuator_controls_status_1 6 | -------------------------------------------------------------------------------- /msg/ActuatorMotors.msg: -------------------------------------------------------------------------------- 1 | # Motor control message 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | uint64 timestamp_sample # the timestamp the data this control response is based on was sampled 7 | 8 | uint16 reversible_flags # bitset which motors are configured to be reversible 9 | 10 | uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 11 | 12 | uint8 NUM_CONTROLS = 12 13 | float32[12] control # range: [-1, 1], where 1 means maximum positive thrust, 14 | # -1 maximum negative (if not supported by the output, <0 maps to NaN), 15 | # and NaN maps to disarmed (stop the motors) 16 | -------------------------------------------------------------------------------- /msg/ActuatorOutputs.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 NUM_ACTUATOR_OUTPUTS = 16 3 | uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking 4 | uint32 noutputs # valid outputs 5 | float32[16] output # output data, in natural output units 6 | 7 | # actuator_outputs_sim is used for SITL, HITL & SIH (with an output range of [-1, 1]) 8 | # TOPICS actuator_outputs actuator_outputs_sim actuator_outputs_debug 9 | -------------------------------------------------------------------------------- /msg/ActuatorServos.msg: -------------------------------------------------------------------------------- 1 | # Servo control message 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | uint64 timestamp_sample # the timestamp the data this control response is based on was sampled 7 | 8 | uint8 NUM_CONTROLS = 8 9 | float32[8] control # range: [-1, 1], where 1 means maximum positive position, 10 | # -1 maximum negative, 11 | # and NaN maps to disarmed 12 | -------------------------------------------------------------------------------- /msg/ActuatorServosTrim.msg: -------------------------------------------------------------------------------- 1 | # Servo trims, added as offset to servo outputs 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint8 NUM_CONTROLS = 8 5 | float32[8] trim # range: [-1, 1] 6 | -------------------------------------------------------------------------------- /msg/ActuatorTest.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # Topic to test individual actuator output functions 4 | 5 | uint8 ACTION_RELEASE_CONTROL = 0 # exit test mode for the given function 6 | uint8 ACTION_DO_CONTROL = 1 # enable actuator test mode 7 | 8 | uint8 FUNCTION_MOTOR1 = 101 9 | uint8 MAX_NUM_MOTORS = 12 10 | uint8 FUNCTION_SERVO1 = 201 11 | uint8 MAX_NUM_SERVOS = 8 12 | 13 | uint8 action # one of ACTION_* 14 | uint16 function # actuator output function 15 | float32 value # range: [-1, 1], where 1 means maximum positive output, 16 | # 0 to center servos or minimum motor thrust, 17 | # -1 maximum negative (if not supported by the motors, <0 maps to NaN), 18 | # and NaN maps to disarmed (stop the motors) 19 | uint32 timeout_ms # timeout in ms after which to exit test mode (if 0, do not time out) 20 | 21 | uint8 ORB_QUEUE_LENGTH = 16 # >= MAX_NUM_MOTORS to support code in esc_calibration 22 | -------------------------------------------------------------------------------- /msg/AdcReport.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 3 | int16[12] channel_id # ADC channel IDs, negative for non-existent, TODO: should be kept same as array index 4 | int32[12] raw_data # ADC channel raw value, accept negative value, valid if channel ID is positive 5 | uint32 resolution # ADC channel resolution 6 | float32 v_ref # ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution) 7 | -------------------------------------------------------------------------------- /msg/Airspeed.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | float32 indicated_airspeed_m_s # indicated airspeed in m/s 5 | 6 | float32 true_airspeed_m_s # true filtered airspeed in m/s 7 | 8 | float32 confidence # confidence value from 0 to 1 for this sensor 9 | -------------------------------------------------------------------------------- /msg/AirspeedValidated.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 1 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid 6 | float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid 7 | float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid 8 | 9 | int8 airspeed_source # Source of currently published airspeed values 10 | int8 DISABLED = -1 11 | int8 GROUND_MINUS_WIND = 0 12 | int8 SENSOR_1 = 1 13 | int8 SENSOR_2 = 2 14 | int8 SENSOR_3 = 3 15 | int8 SYNTHETIC = 4 16 | 17 | # debug states 18 | float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid 19 | float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid 20 | float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] 21 | float32 throttle_filtered # filtered fixed-wing throttle [-] 22 | float32 pitch_filtered # filtered pitch [rad] 23 | -------------------------------------------------------------------------------- /msg/AirspeedWind.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | float32 windspeed_north # Wind component in north / X direction (m/sec) 5 | float32 windspeed_east # Wind component in east / Y direction (m/sec) 6 | 7 | float32 variance_north # Wind estimate error variance in north / X direction (m/sec)**2 - set to zero (no uncertainty) if not estimated 8 | float32 variance_east # Wind estimate error variance in east / Y direction (m/sec)**2 - set to zero (no uncertainty) if not estimated 9 | 10 | float32 tas_innov # True airspeed innovation 11 | float32 tas_innov_var # True airspeed innovation variance 12 | 13 | float32 tas_scale_raw # Estimated true airspeed scale factor (not validated) 14 | float32 tas_scale_raw_var # True airspeed scale factor variance 15 | 16 | float32 tas_scale_validated # Estimated true airspeed scale factor after validation 17 | 18 | float32 beta_innov # Sideslip measurement innovation 19 | float32 beta_innov_var # Sideslip measurement innovation variance 20 | 21 | uint8 source # source of wind estimate 22 | 23 | uint8 SOURCE_AS_BETA_ONLY = 0 # wind estimate only based on synthetic sideslip fusion 24 | uint8 SOURCE_AS_SENSOR_1 = 1 # combined synthetic sideslip and airspeed fusion (data from first airspeed sensor) 25 | uint8 SOURCE_AS_SENSOR_2 = 2 # combined synthetic sideslip and airspeed fusion (data from second airspeed sensor) 26 | uint8 SOURCE_AS_SENSOR_3 = 3 # combined synthetic sideslip and airspeed fusion (data from third airspeed sensor) 27 | -------------------------------------------------------------------------------- /msg/ArmingCheckReply.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 1 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 request_id 6 | uint8 registration_id 7 | 8 | uint8 HEALTH_COMPONENT_INDEX_NONE = 0 9 | 10 | uint8 health_component_index # HEALTH_COMPONENT_INDEX_* 11 | bool health_component_is_present 12 | bool health_component_warning 13 | bool health_component_error 14 | 15 | bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run 16 | 17 | uint8 num_events 18 | 19 | Event[5] events 20 | 21 | # Mode requirements 22 | bool mode_req_angular_velocity 23 | bool mode_req_attitude 24 | bool mode_req_local_alt 25 | bool mode_req_local_position 26 | bool mode_req_local_position_relaxed 27 | bool mode_req_global_position 28 | bool mode_req_global_position_relaxed 29 | bool mode_req_mission 30 | bool mode_req_home_position 31 | bool mode_req_prevent_arming 32 | bool mode_req_manual_control 33 | 34 | 35 | uint8 ORB_QUEUE_LENGTH = 4 36 | -------------------------------------------------------------------------------- /msg/ArmingCheckRequest.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | # broadcast message to request all registered arming checks to be reported 6 | 7 | uint8 request_id 8 | -------------------------------------------------------------------------------- /msg/AutotuneAttitudeControlStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32[5] coeff # coefficients of the identified discrete-time model 4 | float32[5] coeff_var # coefficients' variance of the identified discrete-time model 5 | float32 fitness # fitness of the parameter estimate 6 | float32 innov 7 | float32 dt_model 8 | 9 | float32 kc 10 | float32 ki 11 | float32 kd 12 | float32 kff 13 | float32 att_p 14 | 15 | float32[3] rate_sp 16 | 17 | float32 u_filt 18 | float32 y_filt 19 | 20 | uint8 STATE_IDLE = 0 21 | uint8 STATE_INIT = 1 22 | uint8 STATE_ROLL = 2 23 | uint8 STATE_ROLL_PAUSE = 3 24 | uint8 STATE_PITCH = 4 25 | uint8 STATE_PITCH_PAUSE = 5 26 | uint8 STATE_YAW = 6 27 | uint8 STATE_YAW_PAUSE = 7 28 | uint8 STATE_VERIFICATION = 8 29 | uint8 STATE_APPLY = 9 30 | uint8 STATE_TEST = 10 31 | uint8 STATE_COMPLETE = 11 32 | uint8 STATE_FAIL = 12 33 | uint8 STATE_WAIT_FOR_DISARM = 13 34 | 35 | uint8 state 36 | -------------------------------------------------------------------------------- /msg/BatteryStatus.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | bool connected # Whether or not a battery is connected, based on a voltage threshold 5 | float32 voltage_v # Battery voltage in volts, 0 if unknown 6 | float32 current_a # Battery current in amperes, -1 if unknown 7 | float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown 8 | float32 discharged_mah # Discharged amount in mAh, -1 if unknown 9 | float32 remaining # From 1 to 0, -1 if unknown 10 | float32 scale # Power scaling factor, >= 1, or -1 if unknown 11 | float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown 12 | float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown 13 | uint8 cell_count # Number of cells, 0 if unknown 14 | 15 | uint8 SOURCE_POWER_MODULE = 0 16 | uint8 SOURCE_EXTERNAL = 1 17 | uint8 SOURCE_ESCS = 2 18 | uint8 source # Battery source 19 | uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 20 | uint16 capacity # actual capacity of the battery 21 | uint16 cycle_count # number of discharge cycles the battery has experienced 22 | uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min 23 | uint16 serial_number # serial number of the battery pack 24 | uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 25 | uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%. 26 | uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% 27 | uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. 28 | uint16 interface_error # interface error counter 29 | 30 | float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown 31 | float32 max_cell_voltage_delta # Max difference between individual cell voltages 32 | 33 | bool is_powering_off # Power off event imminent indication, false if unknown 34 | bool is_required # Set if the battery is explicitly required before arming 35 | 36 | 37 | uint8 WARNING_NONE = 0 # no battery low voltage warning active 38 | uint8 WARNING_LOW = 1 # warning of low voltage 39 | uint8 WARNING_CRITICAL = 2 # critical voltage, return / abort immediately 40 | uint8 WARNING_EMERGENCY = 3 # immediate landing required 41 | uint8 WARNING_FAILED = 4 # the battery has failed completely 42 | uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field. 43 | uint8 STATE_CHARGING = 7 # Battery is charging 44 | 45 | uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged 46 | uint8 FAULT_SPIKES = 1 # Voltage spikes 47 | uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed 48 | uint8 FAULT_OVER_CURRENT = 3 # Over-current 49 | uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature 50 | uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault 51 | uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). 52 | uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware 53 | uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system 54 | uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem 55 | uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming 56 | uint8 FAULT_COUNT = 11 # Counter - keep it as last element! 57 | 58 | uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. 59 | uint8 warning # Current battery warning 60 | 61 | uint8 MAX_INSTANCES = 4 62 | 63 | float32 full_charge_capacity_wh # The compensated battery capacity 64 | float32 remaining_capacity_wh # The compensated battery capacity remaining 65 | uint16 over_discharge_count # Number of battery overdischarge 66 | float32 nominal_voltage # Nominal voltage of the battery pack 67 | 68 | float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate 69 | float32 ocv_estimate # [V] Open circuit voltage estimate 70 | float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate 71 | float32 volt_based_soc_estimate # [0, 1] Normalized volt based state of charge estimate 72 | float32 voltage_prediction # [V] Predicted voltage 73 | float32 prediction_error # [V] Prediction error 74 | float32 estimation_covariance_norm # Norm of the covariance matrix 75 | -------------------------------------------------------------------------------- /msg/ButtonEvent.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | bool triggered # Set to true if the event is triggered 3 | 4 | # TOPICS button_event safety_button 5 | 6 | uint8 ORB_QUEUE_LENGTH = 2 7 | -------------------------------------------------------------------------------- /msg/CameraCapture.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_utc # Capture time in UTC / GPS time 3 | uint32 seq # Image sequence number 4 | float64 lat # Latitude in degrees (WGS84) 5 | float64 lon # Longitude in degrees (WGS84) 6 | float32 alt # Altitude (AMSL) 7 | float32 ground_distance # Altitude above ground (meters) 8 | float32[4] q # Attitude of the camera relative to NED earth-fixed frame when using a gimbal, otherwise vehicle attitude 9 | int8 result # 1 for success, 0 for failure, -1 if camera does not provide feedback 10 | -------------------------------------------------------------------------------- /msg/CameraStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 active_sys_id # mavlink system id of the currently active camera 4 | uint8 active_comp_id # mavlink component id of currently active camera 5 | -------------------------------------------------------------------------------- /msg/CameraTrigger.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_utc # UTC timestamp 3 | 4 | uint32 seq # Image sequence number 5 | bool feedback # Trigger feedback from camera 6 | 7 | uint32 ORB_QUEUE_LENGTH = 2 8 | -------------------------------------------------------------------------------- /msg/CanInterfaceStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 interface 3 | 4 | uint64 io_errors 5 | uint64 frames_tx 6 | uint64 frames_rx 7 | -------------------------------------------------------------------------------- /msg/CellularStatus.msg: -------------------------------------------------------------------------------- 1 | # Cellular status 2 | # 3 | # This is currently used only for logging cell status from MAVLink. 4 | 5 | uint64 timestamp # [us] Time since system start. 6 | 7 | uint16 status # [@enum STATUS_FLAG] Status bitmap. 8 | uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable. 9 | uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable. 10 | uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized. 11 | uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked. 12 | uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down. 13 | uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state. 14 | uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state. 15 | uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections. 16 | uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register. 17 | uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use. 18 | uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated. 19 | uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered. 20 | uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected. 21 | 22 | uint8 failure_reason # [@enum FAILURE_REASON] Failure reason. 23 | uint8 FAILURE_REASON_NONE = 0 # No error. 24 | uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown. 25 | uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing. 26 | uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection. 27 | 28 | uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type. 29 | uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None 30 | uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM 31 | uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA 32 | uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA 33 | uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE 34 | 35 | uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value. 36 | uint16 mcc # [@invalid UINT16_MAX] Mobile country code. 37 | uint16 mnc # [@invalid UINT16_MAX] Mobile network code. 38 | uint16 lac # [@invalid 0] Location area code. 39 | -------------------------------------------------------------------------------- /msg/CollisionConstraints.msg: -------------------------------------------------------------------------------- 1 | # Local setpoint constraints in NED frame 2 | # setting something to NaN means that no limit is provided 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | float32[2] original_setpoint # velocities demanded 7 | float32[2] adapted_setpoint # velocities allowed 8 | -------------------------------------------------------------------------------- /msg/ConfigOverrides.msg: -------------------------------------------------------------------------------- 1 | # Configurable overrides by (external) modes or mode executors 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | bool disable_auto_disarm # Prevent the drone from automatically disarming after landing (if configured) 8 | 9 | bool defer_failsafes # Defer all failsafes that can be deferred (until the flag is cleared) 10 | int16 defer_failsafes_timeout_s # Maximum time a failsafe can be deferred. 0 = system default, -1 = no timeout 11 | 12 | 13 | int8 SOURCE_TYPE_MODE = 0 14 | int8 SOURCE_TYPE_MODE_EXECUTOR = 1 15 | int8 source_type 16 | 17 | uint8 source_id # ID depending on source_type 18 | 19 | uint8 ORB_QUEUE_LENGTH = 4 20 | 21 | # TOPICS config_overrides config_overrides_request 22 | -------------------------------------------------------------------------------- /msg/ControlAllocatorStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | bool torque_setpoint_achieved # Boolean indicating whether the 3D torque setpoint was correctly allocated to actuators. 0 if not achieved, 1 if achieved. 4 | float32[3] unallocated_torque # Unallocated torque. Equal to 0 if the setpoint was achieved. 5 | # Computed as: unallocated_torque = torque_setpoint - allocated_torque 6 | 7 | bool thrust_setpoint_achieved # Boolean indicating whether the 3D thrust setpoint was correctly allocated to actuators. 0 if not achieved, 1 if achieved. 8 | float32[3] unallocated_thrust # Unallocated thrust. Equal to 0 if the setpoint was achieved. 9 | # Computed as: unallocated_thrust = thrust_setpoint - allocated_thrust 10 | 11 | int8 ACTUATOR_SATURATION_OK = 0 # The actuator is not saturated 12 | int8 ACTUATOR_SATURATION_UPPER_DYN = 1 # The actuator is saturated (with a value <= the desired value) because it cannot increase its value faster 13 | int8 ACTUATOR_SATURATION_UPPER = 2 # The actuator is saturated (with a value <= the desired value) because it has reached its maximum value 14 | int8 ACTUATOR_SATURATION_LOWER_DYN = -1 # The actuator is saturated (with a value >= the desired value) because it cannot decrease its value faster 15 | int8 ACTUATOR_SATURATION_LOWER = -2 # The actuator is saturated (with a value >= the desired value) because it has reached its minimum value 16 | 17 | int8[16] actuator_saturation # Indicates actuator saturation status. 18 | # Note 1: actuator saturation does not necessarily imply that the thrust setpoint or the torque setpoint were not achieved. 19 | # Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value. 20 | 21 | uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector 22 | -------------------------------------------------------------------------------- /msg/Cpuload.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | float32 load # processor load from 0 to 1 3 | float32 ram_usage # RAM usage from 0 to 1 4 | -------------------------------------------------------------------------------- /msg/DatamanRequest.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 client_id 4 | uint8 request_type # id/read/write/clear 5 | uint8 item # dm_item_t 6 | uint32 index 7 | uint8[56] data 8 | uint32 data_length 9 | -------------------------------------------------------------------------------- /msg/DatamanResponse.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 client_id 4 | uint8 request_type # id/read/write/clear 5 | uint8 item # dm_item_t 6 | uint32 index 7 | uint8[56] data 8 | 9 | uint8 STATUS_SUCCESS = 0 10 | uint8 STATUS_FAILURE_ID_ERR = 1 11 | uint8 STATUS_FAILURE_NO_DATA = 2 12 | uint8 STATUS_FAILURE_READ_FAILED = 3 13 | uint8 STATUS_FAILURE_WRITE_FAILED = 4 14 | uint8 STATUS_FAILURE_CLEAR_FAILED = 5 15 | uint8 status 16 | -------------------------------------------------------------------------------- /msg/DebugArray.msg: -------------------------------------------------------------------------------- 1 | uint8 ARRAY_SIZE = 58 2 | uint64 timestamp # time since system start (microseconds) 3 | uint16 id # unique ID of debug array, used to discriminate between arrays 4 | char[10] name # name of the debug array (max. 10 characters) 5 | float32[58] data # data 6 | -------------------------------------------------------------------------------- /msg/DebugKeyValue.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | char[10] key # max. 10 characters as key / name 3 | float32 value # the value to send as debug output 4 | -------------------------------------------------------------------------------- /msg/DebugValue.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | int8 ind # index of debug variable 3 | float32 value # the value to send as debug output 4 | -------------------------------------------------------------------------------- /msg/DebugVect.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | char[10] name # max. 10 characters as key / name 3 | float32 x # x value 4 | float32 y # y value 5 | float32 z # z value 6 | -------------------------------------------------------------------------------- /msg/DifferentialPressure.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 differential_pressure_pa # differential pressure reading in Pascals (may be negative) 7 | 8 | float32 temperature # Temperature provided by sensor in degrees Celsius, NAN if unknown 9 | 10 | uint32 error_count # Number of errors detected by driver 11 | -------------------------------------------------------------------------------- /msg/DistanceSensor.msg: -------------------------------------------------------------------------------- 1 | # DISTANCE_SENSOR message data 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 6 | 7 | float32 min_distance # Minimum distance the sensor can measure (in m) 8 | float32 max_distance # Maximum distance the sensor can measure (in m) 9 | float32 current_distance # Current distance reading (in m) 10 | float32 variance # Measurement variance (in m^2), 0 for unknown / invalid readings 11 | int8 signal_quality # Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality. 12 | 13 | uint8 type # Type from MAV_DISTANCE_SENSOR enum 14 | uint8 MAV_DISTANCE_SENSOR_LASER = 0 15 | uint8 MAV_DISTANCE_SENSOR_ULTRASOUND = 1 16 | uint8 MAV_DISTANCE_SENSOR_INFRARED = 2 17 | uint8 MAV_DISTANCE_SENSOR_RADAR = 3 18 | 19 | float32 h_fov # Sensor horizontal field of view (rad) 20 | float32 v_fov # Sensor vertical field of view (rad) 21 | float32[4] q # Quaterion sensor orientation with respect to the vehicle body frame to specify the orientation ROTATION_CUSTOM 22 | 23 | uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum 24 | 25 | uint8 ROTATION_YAW_0 = 0 # MAV_SENSOR_ROTATION_NONE 26 | uint8 ROTATION_YAW_45 = 1 # MAV_SENSOR_ROTATION_YAW_45 27 | uint8 ROTATION_YAW_90 = 2 # MAV_SENSOR_ROTATION_YAW_90 28 | uint8 ROTATION_YAW_135 = 3 # MAV_SENSOR_ROTATION_YAW_135 29 | uint8 ROTATION_YAW_180 = 4 # MAV_SENSOR_ROTATION_YAW_180 30 | uint8 ROTATION_YAW_225 = 5 # MAV_SENSOR_ROTATION_YAW_225 31 | uint8 ROTATION_YAW_270 = 6 # MAV_SENSOR_ROTATION_YAW_270 32 | uint8 ROTATION_YAW_315 = 7 # MAV_SENSOR_ROTATION_YAW_315 33 | 34 | uint8 ROTATION_FORWARD_FACING = 0 # MAV_SENSOR_ROTATION_NONE 35 | uint8 ROTATION_RIGHT_FACING = 2 # MAV_SENSOR_ROTATION_YAW_90 36 | uint8 ROTATION_BACKWARD_FACING = 4 # MAV_SENSOR_ROTATION_YAW_180 37 | uint8 ROTATION_LEFT_FACING = 6 # MAV_SENSOR_ROTATION_YAW_270 38 | 39 | uint8 ROTATION_UPWARD_FACING = 24 # MAV_SENSOR_ROTATION_PITCH_90 40 | uint8 ROTATION_DOWNWARD_FACING = 25 # MAV_SENSOR_ROTATION_PITCH_270 41 | 42 | uint8 ROTATION_CUSTOM = 100 # MAV_SENSOR_ROTATION_CUSTOM 43 | 44 | uint8 mode 45 | uint8 MODE_UNKNOWN = 0 46 | uint8 MODE_ENABLED = 1 47 | uint8 MODE_DISABLED = 2 48 | -------------------------------------------------------------------------------- /msg/DistanceSensorModeChangeRequest.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 request_on_off # request to disable/enable the distance sensor 4 | uint8 REQUEST_OFF = 0 5 | uint8 REQUEST_ON = 1 6 | -------------------------------------------------------------------------------- /msg/Ekf2Timestamps.msg: -------------------------------------------------------------------------------- 1 | # this message contains the (relative) timestamps of the sensor inputs used by EKF2. 2 | # It can be used for reproducible replay. 3 | 4 | # the timestamp field is the ekf2 reference time and matches the timestamp of 5 | # the sensor_combined topic. 6 | 7 | uint64 timestamp # time since system start (microseconds) 8 | 9 | int16 RELATIVE_TIMESTAMP_INVALID = 32767 # (0x7fff) If one of the relative timestamps 10 | # is set to this value, it means the associated sensor values did not update 11 | 12 | # timestamps are relative to the main timestamp and are in 0.1 ms (timestamp + 13 | # *_timestamp_rel = absolute timestamp). For int16, this allows a maximum 14 | # difference of +-3.2s to the sensor_combined topic. 15 | 16 | int16 airspeed_timestamp_rel 17 | int16 airspeed_validated_timestamp_rel 18 | int16 distance_sensor_timestamp_rel 19 | int16 optical_flow_timestamp_rel 20 | int16 vehicle_air_data_timestamp_rel 21 | int16 vehicle_magnetometer_timestamp_rel 22 | int16 visual_odometry_timestamp_rel 23 | 24 | # Note: this is a high-rate logged topic, so it needs to be as small as possible 25 | -------------------------------------------------------------------------------- /msg/EscReport.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint32 esc_errorcount # Number of reported errors by ESC - if supported 3 | int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported 4 | float32 esc_voltage # Voltage measured from current ESC [V] - if supported 5 | float32 esc_current # Current measured from current ESC [A] - if supported 6 | float32 esc_temperature # Temperature measured from current ESC [degC] - if supported 7 | uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver) 8 | uint8 esc_cmdcount # Counter of number of commands 9 | 10 | uint8 esc_state # State of ESC - depend on Vendor 11 | 12 | uint8 actuator_function # actuator output function (one of Motor1...MotorN) 13 | 14 | uint16 failures # Bitmask to indicate the internal ESC faults 15 | int8 esc_power # Applied power 0-100 in % (negative values reserved) 16 | 17 | uint8 FAILURE_OVER_CURRENT = 0 # (1 << 0) 18 | uint8 FAILURE_OVER_VOLTAGE = 1 # (1 << 1) 19 | uint8 FAILURE_MOTOR_OVER_TEMPERATURE = 2 # (1 << 2) 20 | uint8 FAILURE_OVER_RPM = 3 # (1 << 3) 21 | uint8 FAILURE_INCONSISTENT_CMD = 4 # (1 << 4) Set if ESC received an inconsistent command (i.e out of boundaries) 22 | uint8 FAILURE_MOTOR_STUCK = 5 # (1 << 5) 23 | uint8 FAILURE_GENERIC = 6 # (1 << 6) 24 | uint8 FAILURE_MOTOR_WARN_TEMPERATURE = 7 # (1 << 7) 25 | uint8 FAILURE_WARN_ESC_TEMPERATURE = 8 # (1 << 8) 26 | uint8 FAILURE_OVER_ESC_TEMPERATURE = 9 # (1 << 9) 27 | uint8 ESC_FAILURE_COUNT = 10 # Counter - keep it as last element! 28 | -------------------------------------------------------------------------------- /msg/EscStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs 3 | 4 | uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC 5 | uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC 6 | uint8 ESC_CONNECTION_TYPE_ONESHOT = 2 # One Shot PPM 7 | uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C 8 | uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus 9 | uint8 ESC_CONNECTION_TYPE_DSHOT = 5 # DShot 10 | 11 | uint16 counter # incremented by the writing thread everytime new data is stored 12 | 13 | uint8 esc_count # number of connected ESCs 14 | uint8 esc_connectiontype # how ESCs connected to the system 15 | 16 | uint8 esc_online_flags # Bitmask indicating which ESC is online/offline 17 | # esc_online_flags bit 0 : Set to 1 if ESC0 is online 18 | # esc_online_flags bit 1 : Set to 1 if ESC1 is online 19 | # esc_online_flags bit 2 : Set to 1 if ESC2 is online 20 | # esc_online_flags bit 3 : Set to 1 if ESC3 is online 21 | # esc_online_flags bit 4 : Set to 1 if ESC4 is online 22 | # esc_online_flags bit 5 : Set to 1 if ESC5 is online 23 | # esc_online_flags bit 6 : Set to 1 if ESC6 is online 24 | # esc_online_flags bit 7 : Set to 1 if ESC7 is online 25 | 26 | uint8 esc_armed_flags # Bitmask indicating which ESC is armed. For ESC's where the arming state is not known (returned by the ESC), the arming bits should always be set. 27 | 28 | EscReport[8] esc 29 | -------------------------------------------------------------------------------- /msg/EstimatorAidSource1d.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | uint8 estimator_instance 5 | 6 | uint32 device_id 7 | 8 | uint64 time_last_fuse 9 | 10 | float32 observation 11 | float32 observation_variance 12 | 13 | float32 innovation 14 | float32 innovation_filtered 15 | 16 | float32 innovation_variance 17 | 18 | float32 test_ratio # normalized innovation squared 19 | float32 test_ratio_filtered # signed filtered test ratio 20 | 21 | bool innovation_rejected # true if the observation has been rejected 22 | bool fused # true if the sample was successfully fused 23 | 24 | # TOPICS estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt 25 | # TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip 26 | # TOPICS estimator_aid_src_fake_hgt 27 | # TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw 28 | -------------------------------------------------------------------------------- /msg/EstimatorAidSource2d.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | uint8 estimator_instance 5 | 6 | uint32 device_id 7 | 8 | uint64 time_last_fuse 9 | 10 | float64[2] observation 11 | float32[2] observation_variance 12 | 13 | float32[2] innovation 14 | float32[2] innovation_filtered 15 | 16 | float32[2] innovation_variance 17 | 18 | float32[2] test_ratio # normalized innovation squared 19 | float32[2] test_ratio_filtered # signed filtered test ratio 20 | 21 | bool innovation_rejected # true if the observation has been rejected 22 | bool fused # true if the sample was successfully fused 23 | 24 | # TOPICS estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos estimator_aid_src_aux_global_position 25 | # TOPICS estimator_aid_src_aux_vel estimator_aid_src_optical_flow 26 | # TOPICS estimator_aid_src_drag 27 | -------------------------------------------------------------------------------- /msg/EstimatorAidSource3d.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | uint8 estimator_instance 5 | 6 | uint32 device_id 7 | 8 | uint64 time_last_fuse 9 | 10 | float32[3] observation 11 | float32[3] observation_variance 12 | 13 | float32[3] innovation 14 | float32[3] innovation_filtered 15 | 16 | float32[3] innovation_variance 17 | 18 | float32[3] test_ratio # normalized innovation squared 19 | float32[3] test_ratio_filtered # signed filtered test ratio 20 | 21 | bool innovation_rejected # true if the observation has been rejected 22 | bool fused # true if the sample was successfully fused 23 | 24 | # TOPICS estimator_aid_src_ev_vel estimator_aid_src_gnss_vel estimator_aid_src_gravity estimator_aid_src_mag 25 | -------------------------------------------------------------------------------- /msg/EstimatorBias.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | float32 bias # estimated barometric altitude bias (m) 6 | float32 bias_var # estimated barometric altitude bias variance (m^2) 7 | 8 | float32 innov # innovation of the last measurement fusion (m) 9 | float32 innov_var # innovation variance of the last measurement fusion (m^2) 10 | float32 innov_test_ratio # normalized innovation squared test ratio 11 | 12 | # TOPICS estimator_baro_bias estimator_gnss_hgt_bias 13 | -------------------------------------------------------------------------------- /msg/EstimatorBias3d.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32[3] bias # estimated barometric altitude bias (m) 7 | float32[3] bias_var # estimated barometric altitude bias variance (m^2) 8 | 9 | float32[3] innov # innovation of the last measurement fusion (m) 10 | float32[3] innov_var # innovation variance of the last measurement fusion (m^2) 11 | float32[3] innov_test_ratio # normalized innovation squared test ratio 12 | 13 | # TOPICS estimator_bias3d 14 | # TOPICS estimator_ev_pos_bias 15 | -------------------------------------------------------------------------------- /msg/EstimatorEventFlags.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | # information events 5 | uint32 information_event_changes # number of information event changes 6 | bool gps_checks_passed # 0 - true when gps quality checks are passing passed 7 | bool reset_vel_to_gps # 1 - true when the velocity states are reset to the gps measurement 8 | bool reset_vel_to_flow # 2 - true when the velocity states are reset using the optical flow measurement 9 | bool reset_vel_to_vision # 3 - true when the velocity states are reset to the vision system measurement 10 | bool reset_vel_to_zero # 4 - true when the velocity states are reset to zero 11 | bool reset_pos_to_last_known # 5 - true when the position states are reset to the last known position 12 | bool reset_pos_to_gps # 6 - true when the position states are reset to the gps measurement 13 | bool reset_pos_to_vision # 7 - true when the position states are reset to the vision system measurement 14 | bool starting_gps_fusion # 8 - true when the filter starts using gps measurements to correct the state estimates 15 | bool starting_vision_pos_fusion # 9 - true when the filter starts using vision system position measurements to correct the state estimates 16 | bool starting_vision_vel_fusion # 10 - true when the filter starts using vision system velocity measurements to correct the state estimates 17 | bool starting_vision_yaw_fusion # 11 - true when the filter starts using vision system yaw measurements to correct the state estimates 18 | bool yaw_aligned_to_imu_gps # 12 - true when the filter resets the yaw to an estimate derived from IMU and GPS data 19 | bool reset_hgt_to_baro # 13 - true when the vertical position state is reset to the baro measurement 20 | bool reset_hgt_to_gps # 14 - true when the vertical position state is reset to the gps measurement 21 | bool reset_hgt_to_rng # 15 - true when the vertical position state is reset to the rng measurement 22 | bool reset_hgt_to_ev # 16 - true when the vertical position state is reset to the ev measurement 23 | -------------------------------------------------------------------------------- /msg/EstimatorGpsStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | bool checks_passed 5 | 6 | bool check_fail_gps_fix # 0 : insufficient fix type (no 3D solution) 7 | bool check_fail_min_sat_count # 1 : minimum required sat count fail 8 | bool check_fail_max_pdop # 2 : maximum allowed PDOP fail 9 | bool check_fail_max_horz_err # 3 : maximum allowed horizontal position error fail 10 | bool check_fail_max_vert_err # 4 : maximum allowed vertical position error fail 11 | bool check_fail_max_spd_err # 5 : maximum allowed speed error fail 12 | bool check_fail_max_horz_drift # 6 : maximum allowed horizontal position drift fail - requires stationary vehicle 13 | bool check_fail_max_vert_drift # 7 : maximum allowed vertical position drift fail - requires stationary vehicle 14 | bool check_fail_max_horz_spd_err # 8 : maximum allowed horizontal speed fail - requires stationary vehicle 15 | bool check_fail_max_vert_spd_err # 9 : maximum allowed vertical velocity discrepancy fail 16 | bool check_fail_spoofed_gps # 10 : GPS signal is spoofed 17 | 18 | float32 position_drift_rate_horizontal_m_s # Horizontal position rate magnitude (m/s) 19 | float32 position_drift_rate_vertical_m_s # Vertical position rate magnitude (m/s) 20 | float32 filtered_horizontal_speed_m_s # Filtered horizontal velocity magnitude (m/s) 21 | -------------------------------------------------------------------------------- /msg/EstimatorInnovations.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | # GPS 5 | float32[2] gps_hvel # horizontal GPS velocity innovation (m/sec) and innovation variance ((m/sec)**2) 6 | float32 gps_vvel # vertical GPS velocity innovation (m/sec) and innovation variance ((m/sec)**2) 7 | float32[2] gps_hpos # horizontal GPS position innovation (m) and innovation variance (m**2) 8 | float32 gps_vpos # vertical GPS position innovation (m) and innovation variance (m**2) 9 | 10 | # External Vision 11 | float32[2] ev_hvel # horizontal external vision velocity innovation (m/sec) and innovation variance ((m/sec)**2) 12 | float32 ev_vvel # vertical external vision velocity innovation (m/sec) and innovation variance ((m/sec)**2) 13 | float32[2] ev_hpos # horizontal external vision position innovation (m) and innovation variance (m**2) 14 | float32 ev_vpos # vertical external vision position innovation (m) and innovation variance (m**2) 15 | 16 | # Height sensors 17 | float32 rng_vpos # range sensor height innovation (m) and innovation variance (m**2) 18 | float32 baro_vpos # barometer height innovation (m) and innovation variance (m**2) 19 | 20 | # Auxiliary velocity 21 | float32[2] aux_hvel # horizontal auxiliary velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)**2) 22 | 23 | # Optical flow 24 | float32[2] flow # flow innvoation (rad/sec) and innovation variance ((rad/sec)**2) 25 | 26 | # Various 27 | float32 heading # heading innovation (rad) and innovation variance (rad**2) 28 | float32[3] mag_field # earth magnetic field innovation (Gauss) and innovation variance (Gauss**2) 29 | float32[3] gravity # gravity innovation from accelerometerr vector (m/s**2) 30 | float32[2] drag # drag specific force innovation (m/sec**2) and innovation variance ((m/sec)**2) 31 | float32 airspeed # airspeed innovation (m/sec) and innovation variance ((m/sec)**2) 32 | float32 beta # synthetic sideslip innovation (rad) and innovation variance (rad**2) 33 | float32 hagl # height of ground innovation (m) and innovation variance (m**2) 34 | float32 hagl_rate # height of ground rate innovation (m/s) and innovation variance ((m/s)**2) 35 | 36 | # The innovation test ratios are scalar values. In case the field is a vector, 37 | # the test ratio will be put in the first component of the vector. 38 | 39 | # TOPICS estimator_innovations estimator_innovation_variances estimator_innovation_test_ratios 40 | -------------------------------------------------------------------------------- /msg/EstimatorSelectorStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 primary_instance 4 | 5 | uint8 instances_available 6 | 7 | uint32 instance_changed_count 8 | uint64 last_instance_change 9 | 10 | uint32 accel_device_id 11 | uint32 baro_device_id 12 | uint32 gyro_device_id 13 | uint32 mag_device_id 14 | 15 | float32[9] combined_test_ratio 16 | float32[9] relative_test_ratio 17 | bool[9] healthy 18 | 19 | float32[4] accumulated_gyro_error 20 | float32[4] accumulated_accel_error 21 | bool gyro_fault_detected 22 | bool accel_fault_detected 23 | -------------------------------------------------------------------------------- /msg/EstimatorSensorBias.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets, 3 | # scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available). 4 | # 5 | 6 | uint64 timestamp # time since system start (microseconds) 7 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 8 | 9 | # In-run bias estimates (subtract from uncorrected data) 10 | 11 | uint32 gyro_device_id # unique device ID for the sensor that does not change between power cycles 12 | float32[3] gyro_bias # gyroscope in-run bias in body frame (rad/s) 13 | float32 gyro_bias_limit # magnitude of maximum gyroscope in-run bias in body frame (rad/s) 14 | float32[3] gyro_bias_variance 15 | bool gyro_bias_valid 16 | bool gyro_bias_stable # true when the gyro bias estimate is stable enough to use for calibration 17 | 18 | uint32 accel_device_id # unique device ID for the sensor that does not change between power cycles 19 | float32[3] accel_bias # accelerometer in-run bias in body frame (m/s^2) 20 | float32 accel_bias_limit # magnitude of maximum accelerometer in-run bias in body frame (m/s^2) 21 | float32[3] accel_bias_variance 22 | bool accel_bias_valid 23 | bool accel_bias_stable # true when the accel bias estimate is stable enough to use for calibration 24 | 25 | uint32 mag_device_id # unique device ID for the sensor that does not change between power cycles 26 | float32[3] mag_bias # magnetometer in-run bias in body frame (Gauss) 27 | float32 mag_bias_limit # magnitude of maximum magnetometer in-run bias in body frame (Gauss) 28 | float32[3] mag_bias_variance 29 | bool mag_bias_valid 30 | bool mag_bias_stable # true when the mag bias estimate is stable enough to use for calibration 31 | -------------------------------------------------------------------------------- /msg/EstimatorStates.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | float32[25] states # Internal filter states 5 | uint8 n_states # Number of states effectively used 6 | 7 | float32[24] covariances # Diagonal Elements of Covariance Matrix 8 | -------------------------------------------------------------------------------- /msg/Event.msg: -------------------------------------------------------------------------------- 1 | # Events interface 2 | uint32 MESSAGE_VERSION = 1 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | uint32 id # Event ID 7 | uint16 event_sequence # Event sequence number 8 | uint8[25] arguments # (optional) arguments, depend on event id 9 | 10 | uint8 log_levels # Log levels: 4 bits MSB: internal, 4 bits LSB: external 11 | 12 | uint8 ORB_QUEUE_LENGTH = 16 13 | -------------------------------------------------------------------------------- /msg/FailsafeFlags.msg: -------------------------------------------------------------------------------- 1 | # Input flags for the failsafe state machine set by the arming & health checks. 2 | # 3 | # Flags must be named such that false == no failure (e.g. _invalid, _unhealthy, _lost) 4 | # The flag comments are used as label for the failsafe state machine simulation 5 | 6 | uint64 timestamp # time since system start (microseconds) 7 | 8 | # Per-mode requirements 9 | uint32 mode_req_angular_velocity 10 | uint32 mode_req_attitude 11 | uint32 mode_req_local_alt 12 | uint32 mode_req_local_position 13 | uint32 mode_req_local_position_relaxed 14 | uint32 mode_req_global_position 15 | uint32 mode_req_global_position_relaxed 16 | uint32 mode_req_mission 17 | uint32 mode_req_offboard_signal 18 | uint32 mode_req_home_position 19 | uint32 mode_req_wind_and_flight_time_compliance # if set, mode cannot be entered if wind or flight time limit exceeded 20 | uint32 mode_req_prevent_arming # if set, cannot arm while in this mode 21 | uint32 mode_req_manual_control 22 | uint32 mode_req_other # other requirements, not covered above (for external modes) 23 | 24 | 25 | # Mode requirements 26 | bool angular_velocity_invalid # Angular velocity invalid 27 | bool attitude_invalid # Attitude invalid 28 | bool local_altitude_invalid # Local altitude invalid 29 | bool local_position_invalid # Local position estimate invalid 30 | bool local_position_invalid_relaxed # Local position with reduced accuracy requirements invalid (e.g. flying with optical flow) 31 | bool local_velocity_invalid # Local velocity estimate invalid 32 | bool global_position_invalid # Global position estimate invalid 33 | bool global_position_invalid_relaxed # Global position estimate invalid with relaxed accuracy requirements 34 | bool auto_mission_missing # No mission available 35 | bool offboard_control_signal_lost # Offboard signal lost 36 | bool home_position_invalid # No home position available 37 | 38 | # Control links 39 | bool manual_control_signal_lost # Manual control (RC) signal lost 40 | bool gcs_connection_lost # GCS connection lost 41 | 42 | # Battery 43 | uint8 battery_warning # Battery warning level (see BatteryStatus.msg) 44 | bool battery_low_remaining_time # Low battery based on remaining flight time 45 | bool battery_unhealthy # Battery unhealthy 46 | 47 | # Other 48 | bool geofence_breached # Geofence breached (one or multiple) 49 | bool mission_failure # Mission failure 50 | bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) 51 | bool wind_limit_exceeded # Wind limit exceeded 52 | bool flight_time_limit_exceeded # Maximum flight time exceeded 53 | bool position_accuracy_low # Position estimate has dropped below threshold, but is currently still declared valid 54 | bool navigator_failure # Navigator failed to execute a mode 55 | 56 | # Failure detector 57 | bool fd_critical_failure # Critical failure (attitude/altitude limit exceeded, or external ATS) 58 | bool fd_esc_arming_failure # ESC failed to arm 59 | bool fd_imbalanced_prop # Imbalanced propeller detected 60 | bool fd_motor_failure # Motor failure 61 | -------------------------------------------------------------------------------- /msg/FailureDetectorStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # FailureDetector status 4 | bool fd_roll 5 | bool fd_pitch 6 | bool fd_alt 7 | bool fd_ext 8 | bool fd_arm_escs 9 | bool fd_battery 10 | bool fd_imbalanced_prop 11 | bool fd_motor 12 | 13 | float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed) 14 | uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures 15 | -------------------------------------------------------------------------------- /msg/FigureEightStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | float32 major_radius # Major axis radius of the figure eight [m]. Positive values orbit clockwise, negative values orbit counter-clockwise. 3 | float32 minor_radius # Minor axis radius of the figure eight [m]. 4 | float32 orientation # Orientation of the major axis of the figure eight [rad]. 5 | uint8 frame # The coordinate system of the fields: x, y, z. 6 | int32 x # X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. 7 | int32 y # Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters * 1e4, global = latitude in degrees * 1e7. 8 | float32 z # Altitude of center point. Coordinate system depends on frame field. 9 | -------------------------------------------------------------------------------- /msg/FixedWingLateralGuidanceStatus.msg: -------------------------------------------------------------------------------- 1 | # Fixed Wing Lateral Guidance Status message 2 | # Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | float32 course_setpoint # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. Set by guidance law 7 | float32 lateral_acceleration_ff # [m/s^2] [FRD] lateral acceleration demand only for maintaining curvature 8 | float32 bearing_feas # [@range 0,1] bearing feasibility 9 | float32 bearing_feas_on_track # [@range 0,1] on-track bearing feasibility 10 | float32 signed_track_error # [m] signed track error 11 | float32 track_error_bound # [m] track error bound 12 | float32 adapted_period # [s] adapted period (if auto-tuning enabled) 13 | uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) 14 | -------------------------------------------------------------------------------- /msg/FixedWingLateralSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Fixed Wing Lateral Setpoint message 2 | # Used by the fw_lateral_longitudinal_control module 3 | # At least one of course, airspeed_direction, or lateral_acceleration must be finite. 4 | 5 | uint32 MESSAGE_VERSION = 0 6 | 7 | uint64 timestamp # time since system start (microseconds) 8 | 9 | float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. 10 | float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. 11 | float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. 12 | -------------------------------------------------------------------------------- /msg/FixedWingLateralStatus.msg: -------------------------------------------------------------------------------- 1 | # Fixed Wing Lateral Status message 2 | # Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint 7 | float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint 8 | -------------------------------------------------------------------------------- /msg/FixedWingLongitudinalSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Fixed Wing Longitudinal Setpoint message 2 | # Used by the fw_lateral_longitudinal_control module 3 | # If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. 4 | # If both altitude and height_rate are NAN, the controller maintains the current altitude. 5 | 6 | uint32 MESSAGE_VERSION = 0 7 | 8 | uint64 timestamp # time since system start (microseconds) 9 | 10 | float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite 11 | float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly 12 | float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used 13 | float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller 14 | float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller 15 | -------------------------------------------------------------------------------- /msg/FixedWingRunwayControl.msg: -------------------------------------------------------------------------------- 1 | # Auxiliary control fields for fixed-wing runway takeoff/landing 2 | 3 | # Passes information from the FixedWingModeManager to the FixedWingAttitudeController 4 | 5 | uint64 timestamp # [us] time since system start 6 | 7 | bool wheel_steering_enabled # Flag that enables the wheel steering. 8 | float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. 9 | -------------------------------------------------------------------------------- /msg/FlightPhaseEstimation.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 flight_phase # Estimate of current flight phase 4 | 5 | uint8 FLIGHT_PHASE_UNKNOWN = 0 # vehicle flight phase is unknown 6 | uint8 FLIGHT_PHASE_LEVEL = 1 # Vehicle is in level flight 7 | uint8 FLIGHT_PHASE_DESCEND = 2 # vehicle is in descend 8 | uint8 FLIGHT_PHASE_CLIMB = 3 # vehicle is climbing 9 | -------------------------------------------------------------------------------- /msg/FollowTarget.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float64 lat # target position (deg * 1e7) 4 | float64 lon # target position (deg * 1e7) 5 | float32 alt # target position 6 | 7 | float32 vy # target vel in y 8 | float32 vx # target vel in x 9 | float32 vz # target vel in z 10 | 11 | uint8 est_cap # target reporting capabilities 12 | -------------------------------------------------------------------------------- /msg/FollowTargetEstimator.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 last_filter_reset_timestamp # time of last filter reset (microseconds) 3 | 4 | bool valid # True if estimator states are okay to be used 5 | bool stale # True if estimator stopped receiving follow_target messages for some time. The estimate can still be valid, though it might be inaccurate. 6 | 7 | float64 lat_est # Estimated target latitude 8 | float64 lon_est # Estimated target longitude 9 | float32 alt_est # Estimated target altitude 10 | 11 | float32[3] pos_est # Estimated target NED position (m) 12 | float32[3] vel_est # Estimated target NED velocity (m/s) 13 | float32[3] acc_est # Estimated target NED acceleration (m^2/s) 14 | 15 | uint64 prediction_count 16 | uint64 fusion_count 17 | -------------------------------------------------------------------------------- /msg/FollowTargetStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # [microseconds] time since system start 2 | 3 | float32 tracked_target_course # [rad] Tracked target course in NED local frame (North is course zero) 4 | float32 follow_angle # [rad] Current follow angle setting 5 | 6 | float32 orbit_angle_setpoint # [rad] Current orbit angle setpoint from the smooth trajectory generator 7 | float32 angular_rate_setpoint # [rad/s] Angular rate commanded from Jerk-limited Orbit Angle trajectory for Orbit Angle 8 | 9 | float32[3] desired_position_raw # [m] Raw 'idealistic' desired drone position if a drone could teleport from place to places 10 | 11 | bool in_emergency_ascent # [bool] True when doing emergency ascent (when distance to ground is below safety altitude) 12 | float32 gimbal_pitch # [rad] Gimbal pitch commanded to track target in the center of the frame 13 | -------------------------------------------------------------------------------- /msg/FuelTankStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 maximum_fuel_capacity # maximum fuel capacity. Must always be provided, either from the driver or a parameter 4 | float32 consumed_fuel # consumed fuel, NaN if not measured. Should not be inferred from the max fuel capacity 5 | float32 fuel_consumption_rate # fuel consumption rate, NaN if not measured 6 | 7 | uint8 percent_remaining # percentage of remaining fuel, UINT8_MAX if not provided 8 | float32 remaining_fuel # remaining fuel, NaN if not measured. Should not be inferred from the max fuel capacity 9 | 10 | uint8 fuel_tank_id # identifier for the fuel tank. Must match ID of other messages for same fuel system. 0 by default when only a single tank exists 11 | 12 | uint32 fuel_type # type of fuel based on MAV_FUEL_TYPE enum. Set to MAV_FUEL_TYPE_UNKNOWN if unknown or it does not fit the provided types 13 | uint8 MAV_FUEL_TYPE_UNKNOWN = 0 # fuel type not specified. Fuel levels are normalized (i.e., maximum is 1, and other levels are relative to 1). 14 | uint8 MAV_FUEL_TYPE_LIQUID = 1 # represents generic liquid fuels, such as gasoline or diesel. Fuel levels are measured in millilitres (ml), and flow rates in millilitres per second (ml/s). 15 | uint8 MAV_FUEL_TYPE_GAS = 2 # represents a gas fuel, such as hydrogen, methane, or propane. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s). 16 | 17 | float32 temperature # fuel temperature in Kelvin, NaN if not measured 18 | -------------------------------------------------------------------------------- /msg/GeneratorStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | 4 | uint64 STATUS_FLAG_OFF = 1 # Generator is off. 5 | uint64 STATUS_FLAG_READY = 2 # Generator is ready to start generating power. 6 | uint64 STATUS_FLAG_GENERATING = 4 # Generator is generating power. 7 | uint64 STATUS_FLAG_CHARGING = 8 # Generator is charging the batteries (generating enough power to charge and provide the load). 8 | uint64 STATUS_FLAG_REDUCED_POWER = 16 # Generator is operating at a reduced maximum power. 9 | uint64 STATUS_FLAG_MAXPOWER = 32 # Generator is providing the maximum output. 10 | uint64 STATUS_FLAG_OVERTEMP_WARNING = 64 # Generator is near the maximum operating temperature, cooling is insufficient. 11 | uint64 STATUS_FLAG_OVERTEMP_FAULT = 128 # Generator hit the maximum operating temperature and shutdown. 12 | uint64 STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 # Power electronics are near the maximum operating temperature, cooling is insufficient. 13 | uint64 STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 # Power electronics hit the maximum operating temperature and shutdown. 14 | uint64 STATUS_FLAG_ELECTRONICS_FAULT = 1024 # Power electronics experienced a fault and shutdown. 15 | uint64 STATUS_FLAG_POWERSOURCE_FAULT = 2048 # The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening. 16 | uint64 STATUS_FLAG_COMMUNICATION_WARNING = 4096 # Generator controller having communication problems. 17 | uint64 STATUS_FLAG_COOLING_WARNING = 8192 # Power electronic or generator cooling system error. 18 | uint64 STATUS_FLAG_POWER_RAIL_FAULT = 16384 # Generator controller power rail experienced a fault. 19 | uint64 STATUS_FLAG_OVERCURRENT_FAULT = 32768 # Generator controller exceeded the overcurrent threshold and shutdown to prevent damage. 20 | uint64 STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 # Generator controller detected a high current going into the batteries and shutdown to prevent battery damage. | 21 | uint64 STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 # Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating. 22 | uint64 STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 # Batteries are under voltage (generator will not start). 23 | uint64 STATUS_FLAG_START_INHIBITED = 524288 # Generator start is inhibited by e.g. a safety switch. 24 | uint64 STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 # Generator requires maintenance. 25 | uint64 STATUS_FLAG_WARMING_UP = 2097152 # Generator is not ready to generate yet. 26 | uint64 STATUS_FLAG_IDLE = 4194304 # Generator is idle. 27 | 28 | uint64 status # Status flags 29 | 30 | 31 | float32 battery_current # [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. 32 | float32 load_current # [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided 33 | float32 power_generated # [W] The power being generated. NaN: field not provided 34 | float32 bus_voltage # [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. 35 | float32 bat_current_setpoint # [A] The target battery current. Positive for out. Negative for in. NaN: field not provided 36 | 37 | uint32 runtime # [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. 38 | 39 | int32 time_until_maintenance # [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. 40 | 41 | uint16 generator_speed # [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided. 42 | 43 | int16 rectifier_temperature # [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided. 44 | int16 generator_temperature # [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. 45 | -------------------------------------------------------------------------------- /msg/GeofenceResult.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 GF_ACTION_NONE = 0 # no action on geofence violation 3 | uint8 GF_ACTION_WARN = 1 # critical mavlink message 4 | uint8 GF_ACTION_LOITER = 2 # switch to AUTO|LOITER 5 | uint8 GF_ACTION_RTL = 3 # switch to AUTO|RTL 6 | uint8 GF_ACTION_TERMINATE = 4 # flight termination 7 | uint8 GF_ACTION_LAND = 5 # switch to AUTO|LAND 8 | 9 | bool geofence_max_dist_triggered # true the check for max distance from Home is triggered 10 | bool geofence_max_alt_triggered # true the check for max altitude above Home is triggered 11 | bool geofence_custom_fence_triggered # true the check for custom inclusion/exclusion geofence(s) is triggered 12 | 13 | uint8 geofence_action # action to take when the geofence is breached 14 | -------------------------------------------------------------------------------- /msg/GeofenceStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 geofence_id # loaded geofence id 4 | uint8 status # Current geofence status 5 | 6 | uint8 GF_STATUS_LOADING = 0 7 | uint8 GF_STATUS_READY = 1 8 | -------------------------------------------------------------------------------- /msg/GimbalControls.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 INDEX_ROLL = 0 3 | uint8 INDEX_PITCH = 1 4 | uint8 INDEX_YAW = 2 5 | 6 | uint64 timestamp_sample # the timestamp the data this control response is based on was sampled 7 | float32[3] control 8 | -------------------------------------------------------------------------------- /msg/GimbalDeviceAttitudeStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 target_system 4 | uint8 target_component 5 | uint16 device_flags 6 | 7 | uint16 DEVICE_FLAGS_RETRACT = 1 8 | uint16 DEVICE_FLAGS_NEUTRAL = 2 9 | uint16 DEVICE_FLAGS_ROLL_LOCK = 4 10 | uint16 DEVICE_FLAGS_PITCH_LOCK = 8 11 | uint16 DEVICE_FLAGS_YAW_LOCK = 16 12 | 13 | float32[4] q 14 | float32 angular_velocity_x 15 | float32 angular_velocity_y 16 | float32 angular_velocity_z 17 | 18 | uint32 failure_flags 19 | float32 delta_yaw 20 | float32 delta_yaw_velocity 21 | uint8 gimbal_device_id 22 | 23 | bool received_from_mavlink 24 | -------------------------------------------------------------------------------- /msg/GimbalDeviceInformation.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8[32] vendor_name 4 | uint8[32] model_name 5 | uint8[32] custom_name 6 | uint32 firmware_version 7 | uint32 hardware_version 8 | uint64 uid 9 | 10 | uint16 cap_flags 11 | 12 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 13 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 14 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 15 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 16 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 17 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 18 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 19 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 20 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 21 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 22 | uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 23 | uint32 GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 24 | 25 | uint16 custom_cap_flags 26 | 27 | float32 roll_min # [rad] 28 | float32 roll_max # [rad] 29 | 30 | float32 pitch_min # [rad] 31 | float32 pitch_max # [rad] 32 | 33 | float32 yaw_min # [rad] 34 | float32 yaw_max # [rad] 35 | 36 | uint8 gimbal_device_id 37 | -------------------------------------------------------------------------------- /msg/GimbalDeviceSetAttitude.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 target_system 4 | uint8 target_component 5 | 6 | uint16 flags 7 | uint32 GIMBAL_DEVICE_FLAGS_RETRACT = 1 8 | uint32 GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 9 | uint32 GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 10 | uint32 GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 11 | uint32 GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 12 | 13 | float32[4] q 14 | 15 | float32 angular_velocity_x 16 | float32 angular_velocity_y 17 | float32 angular_velocity_z 18 | -------------------------------------------------------------------------------- /msg/GimbalManagerInformation.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 cap_flags 4 | 5 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 6 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 7 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 8 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 9 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 10 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 11 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 12 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 13 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 14 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 15 | uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 16 | uint32 GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 17 | uint32 GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 18 | uint32 GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 19 | 20 | uint8 gimbal_device_id 21 | 22 | float32 roll_min # [rad] 23 | float32 roll_max # [rad] 24 | 25 | float32 pitch_min # [rad] 26 | float32 pitch_max # [rad] 27 | 28 | float32 yaw_min # [rad] 29 | float32 yaw_max # [rad] 30 | -------------------------------------------------------------------------------- /msg/GimbalManagerSetAttitude.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 origin_sysid 4 | uint8 origin_compid 5 | 6 | uint8 target_system 7 | uint8 target_component 8 | 9 | uint32 GIMBAL_MANAGER_FLAGS_RETRACT = 1 10 | uint32 GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 11 | uint32 GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 12 | uint32 GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 13 | uint32 GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 14 | 15 | uint32 flags 16 | uint8 gimbal_device_id 17 | 18 | float32[4] q 19 | 20 | float32 angular_velocity_x 21 | float32 angular_velocity_y 22 | float32 angular_velocity_z 23 | 24 | uint8 ORB_QUEUE_LENGTH = 2 25 | -------------------------------------------------------------------------------- /msg/GimbalManagerSetManualControl.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 origin_sysid 4 | uint8 origin_compid 5 | 6 | uint8 target_system 7 | uint8 target_component 8 | 9 | uint32 GIMBAL_MANAGER_FLAGS_RETRACT = 1 10 | uint32 GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 11 | uint32 GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 12 | uint32 GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 13 | uint32 GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 14 | 15 | uint32 flags 16 | uint8 gimbal_device_id 17 | 18 | float32 pitch # unitless -1..1, can be NAN 19 | float32 yaw # unitless -1..1, can be NAN 20 | float32 pitch_rate # unitless -1..1, can be NAN 21 | float32 yaw_rate # unitless -1..1, can be NAN 22 | -------------------------------------------------------------------------------- /msg/GimbalManagerStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 flags 4 | uint8 gimbal_device_id 5 | uint8 primary_control_sysid 6 | uint8 primary_control_compid 7 | uint8 secondary_control_sysid 8 | uint8 secondary_control_compid 9 | -------------------------------------------------------------------------------- /msg/GotoSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Position and (optional) heading setpoints with corresponding speed constraints 2 | # Setpoints are intended as inputs to position and heading smoothers, respectively 3 | # Setpoints do not need to be kinematically consistent 4 | # Optional heading setpoints may be specified as controlled by the respective flag 5 | # Unset optional setpoints are not controlled 6 | # Unset optional constraints default to vehicle specifications 7 | 8 | uint32 MESSAGE_VERSION = 0 9 | 10 | uint64 timestamp # time since system start (microseconds) 11 | 12 | # setpoints 13 | float32[3] position # [m] NED local world frame 14 | 15 | bool flag_control_heading # true if heading is to be controlled 16 | float32 heading # (optional) [rad] [-pi,pi] from North 17 | 18 | # constraints 19 | bool flag_set_max_horizontal_speed # true if setting a non-default horizontal speed limit 20 | float32 max_horizontal_speed # (optional) [m/s] maximum speed (absolute) in the NE-plane 21 | 22 | bool flag_set_max_vertical_speed # true if setting a non-default vertical speed limit 23 | float32 max_vertical_speed # (optional) [m/s] maximum speed (absolute) in the D-axis 24 | 25 | bool flag_set_max_heading_rate # true if setting a non-default heading rate limit 26 | float32 max_heading_rate # (optional) [rad/s] maximum heading rate (absolute) 27 | -------------------------------------------------------------------------------- /msg/GpioConfig.msg: -------------------------------------------------------------------------------- 1 | # GPIO configuration 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint32 device_id # Device id 5 | 6 | uint32 mask # Pin mask 7 | uint32 state # Initial pin output state 8 | 9 | # Configuration Mask 10 | # Bit 0-3: Direction: 0=Input, 1=Output 11 | # Bit 4-7: Input Config: 0=Floating, 1=PullUp, 2=PullDown 12 | # Bit 8-12: Output Config: 0=PushPull, 1=OpenDrain 13 | # Bit 13-31: Reserved 14 | uint32 INPUT = 0 # 0x0000 15 | uint32 OUTPUT = 1 # 0x0001 16 | uint32 PULLUP = 16 # 0x0010 17 | uint32 PULLDOWN = 32 # 0x0020 18 | uint32 OPENDRAIN = 256 # 0x0100 19 | 20 | uint32 INPUT_FLOATING = 0 # 0x0000 21 | uint32 INPUT_PULLUP = 16 # 0x0010 22 | uint32 INPUT_PULLDOWN = 32 # 0x0020 23 | 24 | uint32 OUTPUT_PUSHPULL = 0 # 0x0000 25 | uint32 OUTPUT_OPENDRAIN = 256 # 0x0100 26 | uint32 OUTPUT_OPENDRAIN_PULLUP = 272 # 0x0110 27 | 28 | uint32 config 29 | -------------------------------------------------------------------------------- /msg/GpioIn.msg: -------------------------------------------------------------------------------- 1 | # GPIO mask and state 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint32 device_id # Device id 5 | 6 | uint32 state # pin state mask 7 | -------------------------------------------------------------------------------- /msg/GpioOut.msg: -------------------------------------------------------------------------------- 1 | # GPIO mask and state 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint32 device_id # Device id 5 | 6 | uint32 mask # pin mask 7 | uint32 state # pin state mask 8 | -------------------------------------------------------------------------------- /msg/GpioRequest.msg: -------------------------------------------------------------------------------- 1 | # Request GPIO mask to be read 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint32 device_id # Device id 5 | -------------------------------------------------------------------------------- /msg/GpsDump.msg: -------------------------------------------------------------------------------- 1 | # This message is used to dump the raw gps communication to the log. 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 instance # Instance of GNSS receiver 6 | uint8 len # length of data, MSB bit set = message to the gps device, 7 | # clear = message from the device 8 | uint8[79] data # data to write to the log 9 | 10 | uint8 ORB_QUEUE_LENGTH = 8 11 | -------------------------------------------------------------------------------- /msg/GpsInjectData.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 4 | 5 | uint16 len # length of data 6 | uint8 flags # LSB: 1=fragmented 7 | uint8[300] data # data to write to GPS device (RTCM message) 8 | 9 | uint8 ORB_QUEUE_LENGTH = 8 10 | 11 | uint8 MAX_INSTANCES = 2 12 | -------------------------------------------------------------------------------- /msg/Gripper.msg: -------------------------------------------------------------------------------- 1 | ## Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module 2 | 3 | uint64 timestamp 4 | 5 | int8 command # Commanded state for the gripper 6 | int8 COMMAND_GRAB = 0 7 | int8 COMMAND_RELEASE = 1 8 | -------------------------------------------------------------------------------- /msg/HealthReport.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint64 can_arm_mode_flags # bitfield for each flight mode (NAVIGATION_STATE_*) if arming is possible 4 | uint64 can_run_mode_flags # bitfield for each flight mode if it can run 5 | 6 | uint64 health_is_present_flags # flags for each health_component_t 7 | uint64 health_warning_flags 8 | uint64 health_error_flags 9 | # A component is required but missing, if present==0 and error==1 10 | 11 | uint64 arming_check_warning_flags 12 | uint64 arming_check_error_flags 13 | -------------------------------------------------------------------------------- /msg/HeaterStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 device_id 4 | 5 | bool heater_on 6 | bool temperature_target_met 7 | 8 | float32 temperature_sensor 9 | float32 temperature_target 10 | 11 | uint32 controller_period_usec 12 | uint32 controller_time_on_usec 13 | 14 | float32 proportional_value 15 | float32 integrator_value 16 | float32 feed_forward_value 17 | 18 | uint8 MODE_GPIO = 1 19 | uint8 MODE_PX4IO = 2 20 | uint8 mode 21 | -------------------------------------------------------------------------------- /msg/HomePosition.msg: -------------------------------------------------------------------------------- 1 | # GPS home position in WGS84 coordinates. 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | float64 lat # Latitude in degrees 8 | float64 lon # Longitude in degrees 9 | float32 alt # Altitude in meters (AMSL) 10 | 11 | float32 x # X coordinate in meters 12 | float32 y # Y coordinate in meters 13 | float32 z # Z coordinate in meters 14 | 15 | float32 yaw # Yaw angle in radians 16 | 17 | bool valid_alt # true when the altitude has been set 18 | bool valid_hpos # true when the latitude and longitude have been set 19 | bool valid_lpos # true when the local position (xyz) has been set 20 | 21 | bool manual_home # true when home position was set manually 22 | 23 | uint32 update_count # update counter of the home position 24 | -------------------------------------------------------------------------------- /msg/HoverThrustEstimate.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # time of corresponding sensor data last used for this estimate 3 | 4 | float32 hover_thrust # estimated hover thrust [0.1, 0.9] 5 | float32 hover_thrust_var # estimated hover thrust variance 6 | 7 | float32 accel_innov # innovation of the last acceleration fusion 8 | float32 accel_innov_var # innovation variance of the last acceleration fusion 9 | float32 accel_innov_test_ratio # normalized innovation squared test ratio 10 | 11 | float32 accel_noise_var # vertical acceleration noise variance estimated form innovation residual 12 | 13 | bool valid 14 | -------------------------------------------------------------------------------- /msg/InputRc.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 RC_INPUT_SOURCE_UNKNOWN = 0 4 | uint8 RC_INPUT_SOURCE_PX4FMU_PPM = 1 5 | uint8 RC_INPUT_SOURCE_PX4IO_PPM = 2 6 | uint8 RC_INPUT_SOURCE_PX4IO_SPEKTRUM = 3 7 | uint8 RC_INPUT_SOURCE_PX4IO_SBUS = 4 8 | uint8 RC_INPUT_SOURCE_PX4IO_ST24 = 5 9 | uint8 RC_INPUT_SOURCE_MAVLINK = 6 10 | uint8 RC_INPUT_SOURCE_QURT = 7 11 | uint8 RC_INPUT_SOURCE_PX4FMU_SPEKTRUM = 8 12 | uint8 RC_INPUT_SOURCE_PX4FMU_SBUS = 9 13 | uint8 RC_INPUT_SOURCE_PX4FMU_ST24 = 10 14 | uint8 RC_INPUT_SOURCE_PX4FMU_SUMD = 11 15 | uint8 RC_INPUT_SOURCE_PX4FMU_DSM = 12 16 | uint8 RC_INPUT_SOURCE_PX4IO_SUMD = 13 17 | uint8 RC_INPUT_SOURCE_PX4FMU_CRSF = 14 18 | uint8 RC_INPUT_SOURCE_PX4FMU_GHST = 15 19 | 20 | uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. 21 | 22 | uint64 timestamp_last_signal # last valid reception time 23 | 24 | uint8 channel_count # number of channels actually being seen 25 | 26 | int8 RSSI_MAX = 100 27 | int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception 28 | 29 | bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly. 30 | bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usually means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss. 31 | 32 | uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality. 33 | uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality. 34 | uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems 35 | 36 | uint8 input_source # Input source 37 | uint16[18] values # measured pulse widths for each of the supported channels 38 | 39 | int8 link_quality # link quality. Percentage 0-100%. -1 = invalid 40 | float32 rssi_dbm # Actual rssi in units of dBm. NaN = invalid 41 | -------------------------------------------------------------------------------- /msg/InternalCombustionEngineControl.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | bool ignition_on # activate/deactivate ignition (Spark Plug) 4 | float32 throttle_control # [0,1] - Motor should idle with 0. Includes slew rate if enabled. 5 | float32 choke_control # [0,1] - 1 fully closes the air inlet. 6 | float32 starter_engine_control # [0,1] - control value for electric starter motor. 7 | 8 | uint8 user_request # user intent for the ICE being on/off 9 | -------------------------------------------------------------------------------- /msg/InternalCombustionEngineStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 STATE_STOPPED = 0 # The engine is not running. This is the default state. 4 | uint8 STATE_STARTING = 1 # The engine is starting. This is a transient state. 5 | uint8 STATE_RUNNING = 2 # The engine is running normally. 6 | uint8 STATE_FAULT = 3 # The engine can no longer function. 7 | uint8 state 8 | 9 | uint32 FLAG_GENERAL_ERROR = 1 # General error. 10 | 11 | uint32 FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED = 2 # Error of the crankshaft sensor. This flag is optional. 12 | uint32 FLAG_CRANKSHAFT_SENSOR_ERROR = 4 13 | 14 | uint32 FLAG_TEMPERATURE_SUPPORTED = 8 # Temperature levels. These flags are optional 15 | uint32 FLAG_TEMPERATURE_BELOW_NOMINAL = 16 # Under-temperature warning 16 | uint32 FLAG_TEMPERATURE_ABOVE_NOMINAL = 32 # Over-temperature warning 17 | uint32 FLAG_TEMPERATURE_OVERHEATING = 64 # Critical overheating 18 | uint32 FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL = 128 # Exhaust gas over-temperature warning 19 | 20 | uint32 FLAG_FUEL_PRESSURE_SUPPORTED = 256 # Fuel pressure. These flags are optional 21 | uint32 FLAG_FUEL_PRESSURE_BELOW_NOMINAL = 512 # Under-pressure warning 22 | uint32 FLAG_FUEL_PRESSURE_ABOVE_NOMINAL = 1024 # Over-pressure warning 23 | 24 | uint32 FLAG_DETONATION_SUPPORTED = 2048 # Detonation warning. This flag is optional. 25 | uint32 FLAG_DETONATION_OBSERVED = 4096 # Detonation condition observed warning 26 | 27 | uint32 FLAG_MISFIRE_SUPPORTED = 8192 # Misfire warning. This flag is optional. 28 | uint32 FLAG_MISFIRE_OBSERVED = 16384 # Misfire condition observed warning 29 | 30 | uint32 FLAG_OIL_PRESSURE_SUPPORTED = 32768 # Oil pressure. These flags are optional 31 | uint32 FLAG_OIL_PRESSURE_BELOW_NOMINAL = 65536 # Under-pressure warning 32 | uint32 FLAG_OIL_PRESSURE_ABOVE_NOMINAL = 131072 # Over-pressure warning 33 | 34 | uint32 FLAG_DEBRIS_SUPPORTED = 262144 # Debris warning. This flag is optional 35 | uint32 FLAG_DEBRIS_DETECTED = 524288 # Detection of debris warning 36 | uint32 flags 37 | 38 | uint8 engine_load_percent # Engine load estimate, percent, [0, 127] 39 | uint32 engine_speed_rpm # Engine speed, revolutions per minute 40 | float32 spark_dwell_time_ms # Spark dwell time, millisecond 41 | float32 atmospheric_pressure_kpa # Atmospheric (barometric) pressure, kilopascal 42 | float32 intake_manifold_pressure_kpa # Engine intake manifold pressure, kilopascal 43 | float32 intake_manifold_temperature # Engine intake manifold temperature, kelvin 44 | float32 coolant_temperature # Engine coolant temperature, kelvin 45 | float32 oil_pressure # Oil pressure, kilopascal 46 | float32 oil_temperature # Oil temperature, kelvin 47 | float32 fuel_pressure # Fuel pressure, kilopascal 48 | float32 fuel_consumption_rate_cm3pm # Instant fuel consumption estimate, (centimeter^3)/minute 49 | float32 estimated_consumed_fuel_volume_cm3 # Estimate of the consumed fuel since the start of the engine, centimeter^3 50 | uint8 throttle_position_percent # Throttle position, percent 51 | uint8 ecu_index # The index of the publishing ECU 52 | 53 | 54 | uint8 SPARK_PLUG_SINGLE = 0 55 | uint8 SPARK_PLUG_FIRST_ACTIVE = 1 56 | uint8 SPARK_PLUG_SECOND_ACTIVE = 2 57 | uint8 SPARK_PLUG_BOTH_ACTIVE = 3 58 | uint8 spark_plug_usage # Spark plug activity report. 59 | 60 | float32 ignition_timing_deg # Cylinder ignition timing, angular degrees of the crankshaft 61 | float32 injection_time_ms # Fuel injection time, millisecond 62 | float32 cylinder_head_temperature # Cylinder head temperature (CHT), kelvin 63 | float32 exhaust_gas_temperature # Exhaust gas temperature (EGT), kelvin 64 | float32 lambda_coefficient # Estimated lambda coefficient, dimensionless ratio 65 | -------------------------------------------------------------------------------- /msg/IridiumsbdStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 last_at_ok_timestamp # timestamp of the last "OK" received after the "AT" command 3 | uint16 tx_buf_write_index # current size of the tx buffer 4 | uint16 rx_buf_read_index # the rx buffer is parsed up to that index 5 | uint16 rx_buf_end_index # current size of the rx buffer 6 | uint16 failed_sbd_sessions # number of failed sbd sessions 7 | uint16 successful_sbd_sessions # number of successful sbd sessions 8 | uint16 num_tx_buf_reset # number of times the tx buffer was reset 9 | uint8 signal_quality # current signal quality, 0 is no signal, 5 the best 10 | uint8 state # current state of the driver, see the satcom_state of IridiumSBD.h for the definition 11 | bool ring_pending # indicates if a ring call is pending 12 | bool tx_buf_write_pending # indicates if a tx buffer write is pending 13 | bool tx_session_pending # indicates if a tx session is pending 14 | bool rx_read_pending # indicates if a rx read is pending 15 | bool rx_session_pending # indicates if a rx session is pending 16 | -------------------------------------------------------------------------------- /msg/IrlockReport.msg: -------------------------------------------------------------------------------- 1 | # IRLOCK_REPORT message data 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint16 signature 6 | 7 | # When looking along the optical axis of the camera, x points right, y points down, and z points along the optical axis. 8 | float32 pos_x # tan(theta), where theta is the angle between the target and the camera center of projection in camera x-axis 9 | float32 pos_y # tan(theta), where theta is the angle between the target and the camera center of projection in camera y-axis 10 | float32 size_x #/** size of target along camera x-axis in units of tan(theta) **/ 11 | float32 size_y #/** size of target along camera y-axis in units of tan(theta) **/ 12 | -------------------------------------------------------------------------------- /msg/LandingGear.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | int8 GEAR_UP = 1 # landing gear up 4 | int8 GEAR_DOWN = -1 # landing gear down 5 | int8 GEAR_KEEP = 0 # keep the current state 6 | 7 | int8 landing_gear 8 | -------------------------------------------------------------------------------- /msg/LandingGearWheel.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 normalized_wheel_setpoint # negative is turning left, positive turning right [-1, 1] 4 | -------------------------------------------------------------------------------- /msg/LandingTargetInnovations.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | # Innovation of landing target position estimator 3 | float32 innov_x 4 | float32 innov_y 5 | 6 | # Innovation covariance of landing target position estimator 7 | float32 innov_cov_x 8 | float32 innov_cov_y 9 | -------------------------------------------------------------------------------- /msg/LandingTargetPose.msg: -------------------------------------------------------------------------------- 1 | # Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | bool is_static # Flag indicating whether the landing target is static or moving with respect to the ground 6 | 7 | bool rel_pos_valid # Flag showing whether relative position is valid 8 | bool rel_vel_valid # Flag showing whether relative velocity is valid 9 | 10 | float32 x_rel # X/north position of target, relative to vehicle (navigation frame) [meters] 11 | float32 y_rel # Y/east position of target, relative to vehicle (navigation frame) [meters] 12 | float32 z_rel # Z/down position of target, relative to vehicle (navigation frame) [meters] 13 | 14 | float32 vx_rel # X/north velocity of target, relative to vehicle (navigation frame) [meters/second] 15 | float32 vy_rel # Y/east velocity of target, relative to vehicle (navigation frame) [meters/second] 16 | 17 | float32 cov_x_rel # X/north position variance [meters^2] 18 | float32 cov_y_rel # Y/east position variance [meters^2] 19 | 20 | float32 cov_vx_rel # X/north velocity variance [(meters/second)^2] 21 | float32 cov_vy_rel # Y/east velocity variance [(meters/second)^2] 22 | 23 | bool abs_pos_valid # Flag showing whether absolute position is valid 24 | float32 x_abs # X/north position of target, relative to origin (navigation frame) [meters] 25 | float32 y_abs # Y/east position of target, relative to origin (navigation frame) [meters] 26 | float32 z_abs # Z/down position of target, relative to origin (navigation frame) [meters] 27 | -------------------------------------------------------------------------------- /msg/LateralControlConfiguration.msg: -------------------------------------------------------------------------------- 1 | # Fixed Wing Lateral Control Configuration message 2 | # Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. 3 | 4 | uint32 MESSAGE_VERSION = 0 5 | 6 | uint64 timestamp # time since system start (microseconds) 7 | 8 | float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY 9 | -------------------------------------------------------------------------------- /msg/LaunchDetectionStatus.msg: -------------------------------------------------------------------------------- 1 | # Status of the launch detection state machine (fixed-wing only) 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 STATE_WAITING_FOR_LAUNCH = 0 # waiting for launch 6 | uint8 STATE_LAUNCH_DETECTED_DISABLED_MOTOR = 1 # launch detected, but keep motor(s) disabled (e.g. because it can't spin freely while on catapult) 7 | uint8 STATE_FLYING = 2 # launch detected, use normal takeoff/flying configuration 8 | 9 | uint8 launch_detection_state 10 | -------------------------------------------------------------------------------- /msg/LedControl.msg: -------------------------------------------------------------------------------- 1 | # LED control: control a single or multiple LED's. 2 | # These are the externally visible LED's, not the board LED's 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | # colors 7 | uint8 COLOR_OFF = 0 # this is only used in the drivers 8 | uint8 COLOR_RED = 1 9 | uint8 COLOR_GREEN = 2 10 | uint8 COLOR_BLUE = 3 11 | uint8 COLOR_YELLOW = 4 12 | uint8 COLOR_PURPLE = 5 13 | uint8 COLOR_AMBER = 6 14 | uint8 COLOR_CYAN = 7 15 | uint8 COLOR_WHITE = 8 16 | 17 | # LED modes definitions 18 | uint8 MODE_OFF = 0 # turn LED off 19 | uint8 MODE_ON = 1 # turn LED on 20 | uint8 MODE_DISABLED = 2 # disable this priority (switch to lower priority setting) 21 | uint8 MODE_BLINK_SLOW = 3 22 | uint8 MODE_BLINK_NORMAL = 4 23 | uint8 MODE_BLINK_FAST = 5 24 | uint8 MODE_BREATHE = 6 # continuously increase & decrease brightness (solid color if driver does not support it) 25 | uint8 MODE_FLASH = 7 # two fast blinks (on/off) with timing as in MODE_BLINK_FAST and then off for a while 26 | 27 | uint8 MAX_PRIORITY = 2 # maximum priority (minimum is 0) 28 | 29 | 30 | uint8 led_mask # bitmask which LED(s) to control, set to 0xff for all 31 | uint8 color # see COLOR_* 32 | uint8 mode # see MODE_* 33 | uint8 num_blinks # how many times to blink (number of on-off cycles if mode is one of MODE_BLINK_*) . Set to 0 for infinite 34 | # in MODE_FLASH it is the number of cycles. Max number of blinks: 122 and max number of flash cycles: 20 35 | uint8 priority # priority: higher priority events will override current lower priority events (see MAX_PRIORITY) 36 | 37 | uint8 ORB_QUEUE_LENGTH = 8 # needs to match BOARD_MAX_LEDS 38 | -------------------------------------------------------------------------------- /msg/LogMessage.msg: -------------------------------------------------------------------------------- 1 | # A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 severity # log level (same as in the linux kernel, starting with 0) 6 | char[127] text 7 | 8 | uint8 ORB_QUEUE_LENGTH = 4 9 | -------------------------------------------------------------------------------- /msg/LoggerStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 LOGGER_TYPE_FULL = 0 # Normal, full size log 4 | uint8 LOGGER_TYPE_MISSION = 1 # reduced mission log (e.g. for geotagging) 5 | uint8 type 6 | 7 | uint8 BACKEND_FILE = 1 8 | uint8 BACKEND_MAVLINK = 2 9 | uint8 BACKEND_ALL = 3 10 | uint8 backend 11 | 12 | bool is_logging 13 | 14 | float32 total_written_kb # total written to log in kiloBytes 15 | float32 write_rate_kb_s # write rate in kiloBytes/s 16 | 17 | uint32 dropouts # number of failed buffer writes due to buffer overflow 18 | uint32 message_gaps # messages misssed 19 | 20 | uint32 buffer_used_bytes # current buffer fill in Bytes 21 | uint32 buffer_size_bytes # total buffer size in Bytes 22 | 23 | uint8 num_messages 24 | -------------------------------------------------------------------------------- /msg/LongitudinalControlConfiguration.msg: -------------------------------------------------------------------------------- 1 | # Fixed Wing Longitudinal Control Configuration message 2 | # Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages 3 | # and configure the resultant setpoints. 4 | 5 | uint32 MESSAGE_VERSION = 0 6 | 7 | uint64 timestamp # time since system start (microseconds) 8 | 9 | float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN. 10 | float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN. 11 | float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN. 12 | float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN. 13 | float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. 14 | float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. 15 | float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only 16 | bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking 17 | bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller 18 | -------------------------------------------------------------------------------- /msg/MagWorkerData.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint8 MAX_MAGS = 4 5 | 6 | uint32 done_count 7 | uint32 calibration_points_perside 8 | uint64 calibration_interval_perside_us 9 | uint32[4] calibration_counter_total 10 | bool[4] side_data_collected 11 | float32[4] x 12 | float32[4] y 13 | float32[4] z 14 | -------------------------------------------------------------------------------- /msg/MagnetometerBiasEstimate.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32[4] bias_x # estimated X-bias of all the sensors 4 | float32[4] bias_y # estimated Y-bias of all the sensors 5 | float32[4] bias_z # estimated Z-bias of all the sensors 6 | 7 | bool[4] valid # true if the estimator has converged 8 | bool[4] stable 9 | -------------------------------------------------------------------------------- /msg/ManualControlSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 5 | 6 | bool valid 7 | 8 | uint8 SOURCE_UNKNOWN = 0 9 | uint8 SOURCE_RC = 1 # radio control (input_rc) 10 | uint8 SOURCE_MAVLINK_0 = 2 # mavlink instance 0 11 | uint8 SOURCE_MAVLINK_1 = 3 # mavlink instance 1 12 | uint8 SOURCE_MAVLINK_2 = 4 # mavlink instance 2 13 | uint8 SOURCE_MAVLINK_3 = 5 # mavlink instance 3 14 | uint8 SOURCE_MAVLINK_4 = 6 # mavlink instance 4 15 | uint8 SOURCE_MAVLINK_5 = 7 # mavlink instance 5 16 | 17 | uint8 data_source 18 | 19 | # Any of the channels may not be available and be set to NaN 20 | # to indicate that it does not contain valid data. 21 | 22 | # Stick positions [-1,1] 23 | # on a common RC mode 1/2/3/4 remote/joystick the stick deflection: -1 is down/left, 1 is up/right 24 | # Note: QGC sends throttle/z in range [0,1000] - [0,1]. The MAVLink input conversion [0,1] to [-1,1] is at the moment kept backwards compatible. 25 | # Positive values are generally used for: 26 | float32 roll # move right, positive roll rotation, right side down 27 | float32 pitch # move forward, negative pitch rotation, nose down 28 | float32 yaw # positive yaw rotation, clockwise when seen top down 29 | float32 throttle # move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust 30 | 31 | float32 flaps # position of flaps switch/knob/lever [-1, 1] 32 | 33 | float32 aux1 34 | float32 aux2 35 | float32 aux3 36 | float32 aux4 37 | float32 aux5 38 | float32 aux6 39 | 40 | bool sticks_moving 41 | 42 | uint16 buttons # From uint16 buttons field of Mavlink manual_control message 43 | 44 | # TOPICS manual_control_setpoint manual_control_input 45 | # DEPRECATED: float32 x 46 | # DEPRECATED: float32 y 47 | # DEPRECATED: float32 z 48 | # DEPRECATED: float32 r 49 | -------------------------------------------------------------------------------- /msg/ManualControlSwitches.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 4 | 5 | uint8 SWITCH_POS_NONE = 0 # switch is not mapped 6 | uint8 SWITCH_POS_ON = 1 # switch activated (value = 1) 7 | uint8 SWITCH_POS_MIDDLE = 2 # middle position (value = 0) 8 | uint8 SWITCH_POS_OFF = 3 # switch not activated (value = -1) 9 | 10 | uint8 MODE_SLOT_NONE = 0 # no mode slot assigned 11 | uint8 MODE_SLOT_1 = 1 # mode slot 1 selected 12 | uint8 MODE_SLOT_2 = 2 # mode slot 2 selected 13 | uint8 MODE_SLOT_3 = 3 # mode slot 3 selected 14 | uint8 MODE_SLOT_4 = 4 # mode slot 4 selected 15 | uint8 MODE_SLOT_5 = 5 # mode slot 5 selected 16 | uint8 MODE_SLOT_6 = 6 # mode slot 6 selected 17 | uint8 MODE_SLOT_NUM = 6 # number of slots 18 | 19 | uint8 mode_slot # the slot a specific model selector is in 20 | 21 | uint8 arm_switch # arm/disarm switch: _DISARMED_, ARMED 22 | uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL 23 | uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER 24 | uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD 25 | uint8 kill_switch # throttle kill: _NORMAL_, KILL 26 | uint8 gear_switch # landing gear switch: _DOWN_, UP 27 | uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT 28 | 29 | uint8 photo_switch # Photo trigger switch 30 | uint8 video_switch # Photo trigger switch 31 | 32 | uint8 payload_power_switch # Payload power switch 33 | 34 | uint8 engage_main_motor_switch # Engage the main motor (for helicopters) 35 | 36 | uint32 switch_changes # number of switch changes 37 | -------------------------------------------------------------------------------- /msg/MavlinkLog.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | char[127] text 4 | uint8 severity # log level (same as in the linux kernel, starting with 0) 5 | 6 | uint8 ORB_QUEUE_LENGTH = 8 7 | -------------------------------------------------------------------------------- /msg/MavlinkTunnel.msg: -------------------------------------------------------------------------------- 1 | # MAV_TUNNEL_PAYLOAD_TYPE enum 2 | 3 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0 # Encoding of payload unknown 4 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200 # Registered for STorM32 gimbal controller 5 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201 # Registered for STorM32 gimbal controller 6 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202 # Registered for STorM32 gimbal controller 7 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203 # Registered for STorM32 gimbal controller 8 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204 # Registered for STorM32 gimbal controller 9 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205 # Registered for STorM32 gimbal controller 10 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206 # Registered for STorM32 gimbal controller 11 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207 # Registered for STorM32 gimbal controller 12 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208 # Registered for STorM32 gimbal controller 13 | uint8 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209 # Registered for STorM32 gimbal controller 14 | 15 | uint64 timestamp # Time since system start (microseconds) 16 | uint16 payload_type # A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. 17 | uint8 target_system # System ID (can be 0 for broadcast, but this is discouraged) 18 | uint8 target_component # Component ID (can be 0 for broadcast, but this is discouraged) 19 | uint8 payload_length # Length of the data transported in payload 20 | uint8[128] payload # Data itself 21 | 22 | # Topic aliases for known payload types 23 | # TOPICS mavlink_tunnel esc_serial_passthru 24 | -------------------------------------------------------------------------------- /msg/MessageFormatRequest.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # Request to PX4 to get the hash of a message, to check for message compatibility 4 | 5 | uint16 LATEST_PROTOCOL_VERSION = 1 # Current version of this protocol. Increase this whenever the MessageFormatRequest or MessageFormatResponse changes. 6 | 7 | uint16 protocol_version # Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp 8 | 9 | char[50] topic_name # E.g. /fmu/in/vehicle_command 10 | -------------------------------------------------------------------------------- /msg/MessageFormatResponse.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # Response from PX4 with the format of a message 4 | 5 | uint16 protocol_version # Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp 6 | 7 | char[50] topic_name # E.g. /fmu/in/vehicle_command 8 | 9 | bool success 10 | uint32 message_hash # hash over all message fields 11 | -------------------------------------------------------------------------------- /msg/Mission.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 mission_dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1 3 | uint8 fence_dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1 4 | uint8 safepoint_dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1 5 | 6 | uint16 count # count of the missions stored in the dataman 7 | int32 current_seq # default -1, start at the one changed latest 8 | 9 | int32 land_start_index # Index of the land start marker, if unavailable index of the land item, -1 otherwise 10 | int32 land_index # Index of the land item, -1 otherwise 11 | 12 | uint32 mission_id # indicates updates to the mission, reload from dataman if changed 13 | uint32 geofence_id # indicates updates to the geofence, reload from dataman if changed 14 | uint32 safe_points_id # indicates updates to the safe points, reload from dataman if changed 15 | -------------------------------------------------------------------------------- /msg/MissionResult.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 mission_id # Id for the mission for which the result was generated 4 | uint32 geofence_id # Id for the corresponding geofence for which the result was generated (used for mission feasibility) 5 | uint32 home_position_counter # Counter of the home position for which the result was generated (used for mission feasibility) 6 | 7 | int32 seq_reached # Sequence of the mission item which has been reached, default -1 8 | uint16 seq_current # Sequence of the current mission item 9 | uint16 seq_total # Total number of mission items 10 | 11 | bool valid # true if mission is valid 12 | bool warning # true if mission is valid, but has potentially problematic items leading to safety warnings 13 | bool finished # true if mission has been completed 14 | bool failure # true if the mission cannot continue or be completed for some reason 15 | 16 | bool item_do_jump_changed # true if the number of do jumps remaining has changed 17 | uint16 item_changed_index # indicate which item has changed 18 | uint16 item_do_jump_remaining # set to the number of do jumps remaining for that item 19 | 20 | uint8 execution_mode # indicates the mode in which the mission is executed 21 | -------------------------------------------------------------------------------- /msg/ModeCompleted.msg: -------------------------------------------------------------------------------- 1 | # Mode completion result, published by an active mode. 2 | # The possible values of nav_state are defined in the VehicleStatus msg. 3 | # Note that this is not always published (e.g. when a user switches modes or on 4 | # failsafe activation) 5 | 6 | uint32 MESSAGE_VERSION = 0 7 | 8 | uint64 timestamp # time since system start (microseconds) 9 | 10 | 11 | uint8 RESULT_SUCCESS = 0 12 | # [1-99]: reserved 13 | uint8 RESULT_FAILURE_OTHER = 100 # Mode failed (generic error) 14 | 15 | uint8 result # One of RESULT_* 16 | 17 | uint8 nav_state # Source mode (values in VehicleStatus) 18 | -------------------------------------------------------------------------------- /msg/MountOrientation.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad 3 | -------------------------------------------------------------------------------- /msg/NavigatorMissionItem.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint16 sequence_current # Sequence of the current mission item 4 | 5 | uint16 nav_cmd 6 | 7 | float32 latitude 8 | float32 longitude 9 | 10 | float32 time_inside # time that the MAV should stay inside the radius before advancing in seconds 11 | float32 acceptance_radius # default radius in which the mission is accepted as reached in meters 12 | float32 loiter_radius # loiter radius in meters, 0 for a VTOL to hover, negative for counter-clockwise 13 | float32 yaw # in radians NED -PI..+PI, NAN means don't change yaw 14 | float32 altitude # altitude in meters (AMSL) 15 | 16 | uint8 frame # mission frame 17 | uint8 origin # mission item origin (onboard or mavlink) 18 | 19 | bool loiter_exit_xtrack # exit xtrack location: 0 for center of loiter wp, 1 for exit location 20 | bool force_heading # heading needs to be reached 21 | bool altitude_is_relative # true if altitude is relative from start point 22 | bool autocontinue # true if next waypoint should follow after this one 23 | bool vtol_back_transition # part of the vtol back transition sequence 24 | -------------------------------------------------------------------------------- /msg/NavigatorStatus.msg: -------------------------------------------------------------------------------- 1 | # Current status of a Navigator mode 2 | # The possible values of nav_state are defined in the VehicleStatus msg. 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 nav_state # Source mode (values in VehicleStatus) 6 | uint8 failure # Navigator failure enum 7 | 8 | uint8 FAILURE_NONE = 0 9 | uint8 FAILURE_HAGL = 1 # Target altitude exceeds maximum height above ground 10 | -------------------------------------------------------------------------------- /msg/NormalizedUnsignedSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 normalized_setpoint # [0, 1] 4 | 5 | # TOPICS flaps_setpoint spoilers_setpoint 6 | -------------------------------------------------------------------------------- /msg/ObstacleDistance.msg: -------------------------------------------------------------------------------- 1 | # Obstacle distances in front of the sensor. 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint8 frame #Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is North aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. 5 | uint8 MAV_FRAME_GLOBAL = 0 6 | uint8 MAV_FRAME_LOCAL_NED = 1 7 | uint8 MAV_FRAME_BODY_FRD = 12 8 | 9 | uint8 sensor_type # Type from MAV_DISTANCE_SENSOR enum. 10 | uint8 MAV_DISTANCE_SENSOR_LASER = 0 11 | uint8 MAV_DISTANCE_SENSOR_ULTRASOUND = 1 12 | uint8 MAV_DISTANCE_SENSOR_INFRARED = 2 13 | uint8 MAV_DISTANCE_SENSOR_RADAR = 3 14 | 15 | uint16[72] distances # Distance of obstacles around the UAV with index 0 corresponding to local North. A value of 0 means that the obstacle is right in front of the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. 16 | 17 | float32 increment # Angular width in degrees of each array element. 18 | 19 | uint16 min_distance # Minimum distance the sensor can measure in centimeters. 20 | uint16 max_distance # Maximum distance the sensor can measure in centimeters. 21 | 22 | float32 angle_offset # Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. 23 | 24 | # TOPICS obstacle_distance obstacle_distance_fused 25 | -------------------------------------------------------------------------------- /msg/OffboardControlMode.msg: -------------------------------------------------------------------------------- 1 | # Off-board control mode 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | bool position 6 | bool velocity 7 | bool acceleration 8 | bool attitude 9 | bool body_rate 10 | bool thrust_and_torque 11 | bool direct_actuator 12 | -------------------------------------------------------------------------------- /msg/OnboardComputerStatus.msg: -------------------------------------------------------------------------------- 1 | # ONBOARD_COMPUTER_STATUS message data 2 | uint64 timestamp # [us] time since system start (microseconds) 3 | uint32 uptime # [ms] time since system boot of the companion (milliseconds) 4 | 5 | uint8 type # type of onboard computer 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. 6 | 7 | uint8[8] cpu_cores # CPU usage on the component in percent 8 | uint8[10] cpu_combined # Combined CPU usage as the last 10 slices of 100 MS 9 | uint8[4] gpu_cores # GPU usage on the component in percent 10 | uint8[10] gpu_combined # Combined GPU usage as the last 10 slices of 100 MS 11 | int8 temperature_board # [degC] Temperature of the board 12 | int8[8] temperature_core # [degC] Temperature of the CPU core 13 | int16[4] fan_speed # [rpm] Fan speeds 14 | uint32 ram_usage # [MB] Amount of used RAM on the component system 15 | uint32 ram_total # [MB] Total amount of RAM on the component system 16 | uint32[4] storage_type # Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable) 17 | uint32[4] storage_usage # [MB] Amount of used storage space on the component system 18 | uint32[4] storage_total # [MB] Total amount of storage space on the component system 19 | uint32[6] link_type # [Kb/s] Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary 20 | uint32[6] link_tx_rate # [Kb/s] Network traffic from the component system 21 | uint32[6] link_rx_rate # [Kb/s] Network traffic to the component system 22 | uint32[6] link_tx_max # [Kb/s] Network capacity from the component system 23 | uint32[6] link_rx_max # [Kb/s] Network capacity to the component system 24 | -------------------------------------------------------------------------------- /msg/OpenDroneIdArmStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp 2 | uint8 status 3 | char[50] error 4 | -------------------------------------------------------------------------------- /msg/OpenDroneIdOperatorId.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp 2 | uint8[20] id_or_mac 3 | uint8 operator_id_type 4 | char[20] operator_id 5 | -------------------------------------------------------------------------------- /msg/OpenDroneIdSelfId.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp 2 | uint8[20] id_or_mac 3 | uint8 description_type 4 | char[23] description 5 | -------------------------------------------------------------------------------- /msg/OpenDroneIdSystem.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp 2 | uint8[20] id_or_mac 3 | uint8 operator_location_type 4 | uint8 classification_type 5 | int32 operator_latitude 6 | int32 operator_longitude 7 | uint16 area_count 8 | uint16 area_radius 9 | float32 area_ceiling 10 | float32 area_floor 11 | uint8 category_eu 12 | uint8 class_eu 13 | float32 operator_altitude_geo 14 | -------------------------------------------------------------------------------- /msg/OrbTest.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | int32 val 4 | 5 | # TOPICS orb_test orb_multitest 6 | -------------------------------------------------------------------------------- /msg/OrbTestLarge.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | int32 val 4 | 5 | uint8[512] junk 6 | -------------------------------------------------------------------------------- /msg/OrbTestMedium.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | int32 val 4 | 5 | uint8[64] junk 6 | 7 | uint8 ORB_QUEUE_LENGTH = 16 8 | 9 | # TOPICS orb_test_medium orb_test_medium_multi orb_test_medium_wrap_around orb_test_medium_queue orb_test_medium_queue_poll 10 | -------------------------------------------------------------------------------- /msg/OrbitStatus.msg: -------------------------------------------------------------------------------- 1 | # ORBIT_YAW_BEHAVIOUR 2 | uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0 3 | uint8 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1 4 | uint8 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2 5 | uint8 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3 6 | uint8 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4 7 | uint8 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5 8 | 9 | uint64 timestamp # time since system start (microseconds) 10 | float32 radius # Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. [m] 11 | uint8 frame # The coordinate system of the fields: x, y, z. 12 | float64 x # X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. 13 | float64 y # Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters * 1e4, global = latitude in degrees * 1e7. 14 | float32 z # Altitude of center point. Coordinate system depends on frame field. 15 | uint8 yaw_behaviour 16 | -------------------------------------------------------------------------------- /msg/ParameterResetRequest.msg: -------------------------------------------------------------------------------- 1 | # ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote 2 | 3 | uint64 timestamp 4 | uint16 parameter_index 5 | 6 | bool reset_all # If this is true then ignore parameter_index 7 | 8 | uint8 ORB_QUEUE_LENGTH = 4 9 | -------------------------------------------------------------------------------- /msg/ParameterSetUsedRequest.msg: -------------------------------------------------------------------------------- 1 | # ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary 2 | 3 | uint64 timestamp 4 | uint16 parameter_index 5 | 6 | uint8 ORB_QUEUE_LENGTH = 64 7 | -------------------------------------------------------------------------------- /msg/ParameterSetValueRequest.msg: -------------------------------------------------------------------------------- 1 | # ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end 2 | 3 | uint64 timestamp 4 | uint16 parameter_index 5 | 6 | int32 int_value # Optional value for an integer parameter 7 | float32 float_value # Optional value for a float parameter 8 | 9 | uint8 ORB_QUEUE_LENGTH = 32 10 | 11 | # TOPICS parameter_set_value_request parameter_remote_set_value_request parameter_primary_set_value_request 12 | -------------------------------------------------------------------------------- /msg/ParameterSetValueResponse.msg: -------------------------------------------------------------------------------- 1 | # ParameterSetValueResponse : Response to a set value request by either primary or secondary 2 | 3 | uint64 timestamp 4 | uint64 request_timestamp 5 | uint16 parameter_index 6 | 7 | uint8 ORB_QUEUE_LENGTH = 4 8 | 9 | # TOPICS parameter_set_value_response parameter_remote_set_value_response parameter_primary_set_value_response 10 | -------------------------------------------------------------------------------- /msg/ParameterUpdate.msg: -------------------------------------------------------------------------------- 1 | # This message is used to notify the system about one or more parameter changes 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint32 instance # Instance count - constantly incrementing 6 | 7 | uint32 get_count 8 | uint32 set_count 9 | uint32 find_count 10 | uint32 export_count 11 | 12 | uint16 active 13 | uint16 changed 14 | uint16 custom_default 15 | -------------------------------------------------------------------------------- /msg/Ping.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 ping_time # Timestamp of the ping packet 3 | uint32 ping_sequence # Sequence number of the ping packet 4 | uint32 dropped_packets # Number of dropped ping packets 5 | float32 rtt_ms # Round trip time (in ms) 6 | uint8 system_id # System ID of the remote system 7 | uint8 component_id # Component ID of the remote system 8 | -------------------------------------------------------------------------------- /msg/PositionControllerLandingStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # [us] time since system start 2 | float32 lateral_touchdown_offset # [m] lateral touchdown position offset manually commanded during landing 3 | bool flaring # true if the aircraft is flaring 4 | 5 | # abort status is: 6 | # 0 if not aborted 7 | # >0 if aborted, with the singular abort criterion which triggered the landing abort enumerated by the following abort reasons 8 | uint8 abort_status 9 | 10 | # abort reasons 11 | # after the manual operator abort, corresponds to individual bits of param FW_LND_ABORT 12 | uint8 NOT_ABORTED = 0 13 | uint8 ABORTED_BY_OPERATOR = 1 14 | uint8 TERRAIN_NOT_FOUND = 2 # FW_LND_ABORT (1 << 0) 15 | uint8 TERRAIN_TIMEOUT = 3 # FW_LND_ABORT (1 << 1) 16 | uint8 UNKNOWN_ABORT_CRITERION = 4 17 | -------------------------------------------------------------------------------- /msg/PositionControllerStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 nav_roll # Roll setpoint [rad] 4 | float32 nav_pitch # Pitch setpoint [rad] 5 | float32 nav_bearing # Bearing angle[rad] 6 | float32 target_bearing # Bearing angle from aircraft to current target [rad] 7 | float32 xtrack_error # Signed track error [m] 8 | float32 wp_dist # Distance to active (next) waypoint [m] 9 | float32 acceptance_radius # Current horizontal acceptance radius [m] 10 | uint8 type # Current (applied) position setpoint type (see PositionSetpoint.msg) 11 | -------------------------------------------------------------------------------- /msg/PositionSetpoint.msg: -------------------------------------------------------------------------------- 1 | # this file is only used in the position_setpoint triple as a dependency 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 SETPOINT_TYPE_POSITION=0 # position setpoint 6 | uint8 SETPOINT_TYPE_VELOCITY=1 # velocity setpoint 7 | uint8 SETPOINT_TYPE_LOITER=2 # loiter setpoint 8 | uint8 SETPOINT_TYPE_TAKEOFF=3 # takeoff setpoint 9 | uint8 SETPOINT_TYPE_LAND=4 # land setpoint, altitude must be ignored, descend until landing 10 | uint8 SETPOINT_TYPE_IDLE=5 # do nothing, switch off motors or keep at idle speed (MC) 11 | 12 | uint8 LOITER_TYPE_ORBIT=0 # Circular pattern 13 | uint8 LOITER_TYPE_FIGUREEIGHT=1 # Pattern resembling an 8 14 | 15 | bool valid # true if setpoint is valid 16 | uint8 type # setpoint type to adjust behavior of position controller 17 | 18 | float32 vx # local velocity setpoint in m/s in NED 19 | float32 vy # local velocity setpoint in m/s in NED 20 | float32 vz # local velocity setpoint in m/s in NED 21 | 22 | float64 lat # latitude, in deg 23 | float64 lon # longitude, in deg 24 | float32 alt # altitude AMSL, in m 25 | float32 yaw # yaw (only in hover), in rad [-PI..PI), NaN = leave to flight task 26 | 27 | float32 loiter_radius # loiter major axis radius in m 28 | float32 loiter_minor_radius # loiter minor axis radius (used for non-circular loiter shapes) in m 29 | bool loiter_direction_counter_clockwise # loiter direction is clockwise by default and can be changed using this field 30 | float32 loiter_orientation # Orientation of the major axis with respect to true north in rad [-pi,pi) 31 | uint8 loiter_pattern # loitern pattern to follow 32 | 33 | float32 acceptance_radius # horizontal acceptance_radius (meters) 34 | float32 alt_acceptance_radius # vertical acceptance radius, only used for fixed wing guidance, NAN = let guidance choose (meters) 35 | 36 | float32 cruising_speed # the generally desired cruising speed (not a hard constraint) 37 | bool gliding_enabled # commands the vehicle to glide if the capability is available (fixed wing only) 38 | float32 cruising_throttle # the generally desired cruising throttle (not a hard constraint), only has an effect for rover 39 | -------------------------------------------------------------------------------- /msg/PositionSetpointTriplet.msg: -------------------------------------------------------------------------------- 1 | # Global position setpoint triplet in WGS84 coordinates. 2 | # This are the three next waypoints (or just the next two or one). 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | PositionSetpoint previous 7 | PositionSetpoint current 8 | PositionSetpoint next 9 | -------------------------------------------------------------------------------- /msg/PowerButtonState.msg: -------------------------------------------------------------------------------- 1 | # power button state notification message 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 PWR_BUTTON_STATE_IDEL = 0 # Button went up without meeting shutdown button down time (delete event) 6 | uint8 PWR_BUTTON_STATE_DOWN = 1 # Button went Down 7 | uint8 PWR_BUTTON_STATE_UP = 2 # Button went Up 8 | uint8 PWR_BUTTON_STATE_REQUEST_SHUTDOWN = 3 # Button went Up after meeting shutdown button down time 9 | 10 | uint8 event # one of PWR_BUTTON_STATE_* 11 | -------------------------------------------------------------------------------- /msg/PowerMonitor.msg: -------------------------------------------------------------------------------- 1 | # power monitor message 2 | 3 | uint64 timestamp # Time since system start (microseconds) 4 | 5 | float32 voltage_v # Voltage in volts, 0 if unknown 6 | float32 current_a # Current in amperes, -1 if unknown 7 | float32 power_w # power in watts, -1 if unknown 8 | int16 rconf 9 | int16 rsv 10 | int16 rbv 11 | int16 rp 12 | int16 rc 13 | int16 rcal 14 | int16 me 15 | int16 al 16 | -------------------------------------------------------------------------------- /msg/PpsCapture.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) at PPS capture event 2 | uint64 rtc_timestamp # Corrected GPS UTC timestamp at PPS capture event 3 | uint8 pps_rate_exceeded_counter # Increments when PPS dt < 50ms 4 | -------------------------------------------------------------------------------- /msg/PurePursuitStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller 4 | float32 target_bearing # [rad] Target bearing calculated by the pure pursuit controller 5 | float32 crosstrack_error # [m] Shortest distance from the vehicle to the path (Positiv: Vehicle is on the right hand side with respect to the oriented path vector, Negativ: Left of the path) 6 | float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint 7 | float32 bearing_to_waypoint # [rad] Bearing towards current waypoint 8 | -------------------------------------------------------------------------------- /msg/PwmInput.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # Time since system start (microseconds) 2 | uint64 error_count # Timer overcapture error flag (AUX5 or MAIN5) 3 | uint32 pulse_width # Pulse width, timer counts (microseconds) 4 | uint32 period # Period, timer counts (microseconds) 5 | -------------------------------------------------------------------------------- /msg/Px4ioStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint16 free_memory_bytes 4 | 5 | float32 voltage_v # Servo rail voltage in volts 6 | float32 rssi_v # RSSI pin voltage in volts 7 | 8 | # PX4IO status flags (PX4IO_P_STATUS_FLAGS) 9 | bool status_arm_sync 10 | bool status_failsafe 11 | bool status_fmu_initialized 12 | bool status_fmu_ok 13 | bool status_init_ok 14 | bool status_outputs_armed 15 | bool status_raw_pwm 16 | bool status_rc_ok 17 | bool status_rc_dsm 18 | bool status_rc_ppm 19 | bool status_rc_sbus 20 | bool status_rc_st24 21 | bool status_rc_sumd 22 | bool status_safety_button_event # px4io safety button was pressed for longer than 1 second 23 | 24 | # PX4IO alarms (PX4IO_P_STATUS_ALARMS) 25 | bool alarm_pwm_error 26 | bool alarm_rc_lost 27 | 28 | # PX4IO arming (PX4IO_P_SETUP_ARMING) 29 | bool arming_failsafe_custom 30 | bool arming_fmu_armed 31 | bool arming_fmu_prearmed 32 | bool arming_force_failsafe 33 | bool arming_io_arm_ok 34 | bool arming_lockdown 35 | bool arming_termination_failsafe 36 | 37 | uint16[8] pwm 38 | uint16[8] pwm_disarmed 39 | uint16[8] pwm_failsafe 40 | 41 | uint16[8] pwm_rate_hz 42 | 43 | uint16[18] raw_inputs 44 | -------------------------------------------------------------------------------- /msg/QshellReq.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | char[100] cmd 3 | uint32 MAX_STRLEN = 100 4 | uint32 strlen 5 | uint32 request_sequence 6 | -------------------------------------------------------------------------------- /msg/QshellRetval.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | int32 return_value 3 | uint32 return_sequence 4 | -------------------------------------------------------------------------------- /msg/RadioStatus.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint8 rssi # local signal strength 5 | uint8 remote_rssi # remote signal strength 6 | 7 | uint8 txbuf # how full the tx buffer is as a percentage 8 | uint8 noise # background noise level 9 | 10 | uint8 remote_noise # remote background noise level 11 | uint16 rxerrors # receive errors 12 | 13 | uint16 fix # count of error corrected packets 14 | -------------------------------------------------------------------------------- /msg/RateCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # rate controller integrator status 4 | float32 rollspeed_integ 5 | float32 pitchspeed_integ 6 | float32 yawspeed_integ 7 | -------------------------------------------------------------------------------- /msg/RcChannels.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 FUNCTION_THROTTLE = 0 4 | uint8 FUNCTION_ROLL = 1 5 | uint8 FUNCTION_PITCH = 2 6 | uint8 FUNCTION_YAW = 3 7 | uint8 FUNCTION_RETURN = 4 8 | uint8 FUNCTION_LOITER = 5 9 | uint8 FUNCTION_OFFBOARD = 6 10 | uint8 FUNCTION_FLAPS = 7 11 | uint8 FUNCTION_AUX_1 = 8 12 | uint8 FUNCTION_AUX_2 = 9 13 | uint8 FUNCTION_AUX_3 = 10 14 | uint8 FUNCTION_AUX_4 = 11 15 | uint8 FUNCTION_AUX_5 = 12 16 | uint8 FUNCTION_AUX_6 = 13 17 | uint8 FUNCTION_PARAM_1 = 14 18 | uint8 FUNCTION_PARAM_2 = 15 19 | uint8 FUNCTION_PARAM_3_5 = 16 20 | uint8 FUNCTION_KILLSWITCH = 17 21 | uint8 FUNCTION_TRANSITION = 18 22 | uint8 FUNCTION_GEAR = 19 23 | uint8 FUNCTION_ARMSWITCH = 20 24 | uint8 FUNCTION_FLTBTN_SLOT_1 = 21 25 | uint8 FUNCTION_FLTBTN_SLOT_2 = 22 26 | uint8 FUNCTION_FLTBTN_SLOT_3 = 23 27 | uint8 FUNCTION_FLTBTN_SLOT_4 = 24 28 | uint8 FUNCTION_FLTBTN_SLOT_5 = 25 29 | uint8 FUNCTION_FLTBTN_SLOT_6 = 26 30 | uint8 FUNCTION_ENGAGE_MAIN_MOTOR = 27 31 | uint8 FUNCTION_PAYLOAD_POWER = 28 32 | 33 | uint8 FUNCTION_FLTBTN_SLOT_COUNT = 6 34 | 35 | uint64 timestamp_last_valid # Timestamp of last valid RC signal 36 | float32[18] channels # Scaled to -1..1 (throttle: 0..1) 37 | uint8 channel_count # Number of valid channels 38 | int8[29] function # Functions mapping 39 | uint8 rssi # Receive signal strength index 40 | bool signal_lost # Control signal lost, should be checked together with topic timeout 41 | uint32 frame_drop_count # Number of dropped frames 42 | -------------------------------------------------------------------------------- /msg/RcParameterMap.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 RC_PARAM_MAP_NCHAN = 3 # This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h 3 | uint8 PARAM_ID_LEN = 16 # corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 4 | 5 | bool[3] valid #true for RC-Param channels which are mapped to a param 6 | int32[3] param_index # corresponding param index, this field is ignored if set to -1, in this case param_id will be used 7 | char[51] param_id # MAP_NCHAN * (ID_LEN + 1) chars, corresponding param id, null terminated 8 | float32[3] scale # scale to map the RC input [-1, 1] to a parameter value 9 | float32[3] value0 # initial value around which the parameter value is changed 10 | float32[3] value_min # minimal parameter value 11 | float32[3] value_max # minimal parameter value 12 | -------------------------------------------------------------------------------- /msg/RegisterExtComponentReply.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint64 request_id # ID from the request 6 | char[25] name # name from the request 7 | 8 | uint16 px4_ros2_api_version 9 | 10 | bool success 11 | int8 arming_check_id # arming check registration ID (-1 if invalid) 12 | int8 mode_id # assigned mode ID (-1 if invalid) 13 | int8 mode_executor_id # assigned mode executor ID (-1 if invalid) 14 | 15 | uint8 ORB_QUEUE_LENGTH = 2 16 | -------------------------------------------------------------------------------- /msg/RegisterExtComponentRequest.msg: -------------------------------------------------------------------------------- 1 | # Request to register an external component 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | uint64 request_id # ID, set this to a random value 8 | char[25] name # either the requested mode name, or component name 9 | 10 | uint16 LATEST_PX4_ROS2_API_VERSION = 1 # API version compatibility. Increase this on a breaking semantic change. Changes to any message field are detected separately and do not require an API version change. 11 | 12 | uint16 px4_ros2_api_version # Set to LATEST_PX4_ROS2_API_VERSION 13 | 14 | # Components to be registered 15 | bool register_arming_check 16 | bool register_mode # registering a mode also requires arming_check to be set 17 | bool register_mode_executor # registering an executor also requires a mode to be registered (which is the owned mode by the executor) 18 | 19 | bool enable_replace_internal_mode # set to true if an internal mode should be replaced 20 | uint8 replace_internal_mode # vehicle_status::NAVIGATION_STATE_* 21 | bool activate_mode_immediately # switch to the registered mode (can only be set in combination with an executor) 22 | 23 | 24 | uint8 ORB_QUEUE_LENGTH = 2 25 | -------------------------------------------------------------------------------- /msg/RoverAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 yaw_setpoint # [rad] Expressed in NED frame 4 | -------------------------------------------------------------------------------- /msg/RoverAttitudeStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 measured_yaw # [rad/s] Measured yaw rate 4 | float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates) 5 | -------------------------------------------------------------------------------- /msg/RoverPositionSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32[2] position_ned # 2-dimensional position setpoint in NED frame [m] 4 | float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position) 5 | float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed) 6 | float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero) 7 | 8 | float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw) 9 | -------------------------------------------------------------------------------- /msg/RoverRateSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame 4 | -------------------------------------------------------------------------------- /msg/RoverRateStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 measured_yaw_rate # [rad/s] Measured yaw rate 4 | float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates) 5 | float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller 6 | -------------------------------------------------------------------------------- /msg/RoverSteeringSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Ackermann only, Positiv: Steer right, Negativ: Steer left) 4 | 5 | float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Differential/Mecanum only, Positiv = Turn right, Negativ: Turn left) 6 | -------------------------------------------------------------------------------- /msg/RoverThrottleSetpoint.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards) 5 | float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left) 6 | -------------------------------------------------------------------------------- /msg/RoverVelocitySetpoint.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative) 4 | float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction] 5 | float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame 6 | -------------------------------------------------------------------------------- /msg/RoverVelocityStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards 4 | float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards 5 | float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction 6 | float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only) 7 | float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only) 8 | float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only) 9 | -------------------------------------------------------------------------------- /msg/Rpm.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # rpm values of 0.0 mean within a timeout there is no movement measured 4 | float32 rpm_estimate # filtered revolutions per minute 5 | float32 rpm_raw 6 | -------------------------------------------------------------------------------- /msg/RtlStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 safe_points_id # unique ID of active set of safe_point_items 4 | bool is_evaluation_pending # flag if the RTL point needs reevaluation (e.g. new safe points available, but need loading). 5 | 6 | bool has_vtol_approach # flag if approaches are defined for current RTL_TYPE parameter setting 7 | 8 | uint8 rtl_type # Type of RTL chosen 9 | uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode 10 | 11 | uint8 RTL_STATUS_TYPE_NONE=0 # pending if evaluation can't pe performed currently e.g. when it is still loading the safe points 12 | uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe point or home position 13 | uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # going straight to the beginning of the mission landing 14 | uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # Following the mission from start index to mission landing. Start index is current WP if in Mission mode, and closest WP otherwise. 15 | uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # Following the mission in reverse from start index to the beginning of the mission. Start index is previous WP if in Mission mode, and closest WP otherwise. 16 | -------------------------------------------------------------------------------- /msg/RtlTimeEstimate.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | bool valid # Flag indicating whether the time estiamtes are valid 4 | float32 time_estimate # [s] Estimated time for RTL 5 | float32 safe_time_estimate # [s] Same as time_estimate, but with safety factor and safety margin included (factor*t + margin) 6 | -------------------------------------------------------------------------------- /msg/SatelliteInfo.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint8 SAT_INFO_MAX_SATELLITES = 20 3 | 4 | uint8 count # Number of satellites visible to the receiver 5 | uint8[20] svid # Space vehicle ID [1..255], see scheme below 6 | uint8[20] used # 0: Satellite not used, 1: used for navigation 7 | uint8[20] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite 8 | uint8[20] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg. 9 | uint8[20] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. 10 | uint8[20] prn # Satellite PRN code assignment, (psuedorandom number SBAS, valid codes are 120-144) 11 | -------------------------------------------------------------------------------- /msg/SensorAccel.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 x # acceleration in the FRD board frame X-axis in m/s^2 7 | float32 y # acceleration in the FRD board frame Y-axis in m/s^2 8 | float32 z # acceleration in the FRD board frame Z-axis in m/s^2 9 | 10 | float32 temperature # temperature in degrees Celsius 11 | 12 | uint32 error_count 13 | 14 | uint8[3] clip_counter # clip count per axis in the sample period 15 | 16 | uint8 samples # number of raw samples that went into this message 17 | 18 | uint8 ORB_QUEUE_LENGTH = 8 19 | -------------------------------------------------------------------------------- /msg/SensorAccelFifo.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 dt # delta time between samples (microseconds) 7 | float32 scale 8 | 9 | uint8 samples # number of valid samples 10 | 11 | int16[32] x # acceleration in the FRD board frame X-axis in m/s^2 12 | int16[32] y # acceleration in the FRD board frame Y-axis in m/s^2 13 | int16[32] z # acceleration in the FRD board frame Z-axis in m/s^2 14 | -------------------------------------------------------------------------------- /msg/SensorAirflow.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 3 | float32 speed # the speed being reported by the wind / airflow sensor 4 | float32 direction # the direction being reported by the wind / airflow sensor 5 | uint8 status # Status code from the sensor 6 | -------------------------------------------------------------------------------- /msg/SensorBaro.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 pressure # static pressure measurement in Pascals 7 | 8 | float32 temperature # temperature in degrees Celsius 9 | 10 | uint32 error_count 11 | 12 | uint8 ORB_QUEUE_LENGTH = 4 13 | -------------------------------------------------------------------------------- /msg/SensorCombined.msg: -------------------------------------------------------------------------------- 1 | # Sensor readings in SI-unit form. 2 | # These fields are scaled and offset-compensated where possible and do not 3 | # change with board revisions and sensor updates. 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid 8 | 9 | # gyro timstamp is equal to the timestamp of the message 10 | float32[3] gyro_rad # average angular rate measured in the FRD body frame XYZ-axis in rad/s over the last gyro sampling period 11 | uint32 gyro_integral_dt # gyro measurement sampling period in microseconds 12 | 13 | int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp 14 | float32[3] accelerometer_m_s2 # average value acceleration measured in the FRD body frame XYZ-axis in m/s^2 over the last accelerometer sampling period 15 | uint32 accelerometer_integral_dt # accelerometer measurement sampling period in microseconds 16 | 17 | uint8 CLIPPING_X = 1 18 | uint8 CLIPPING_Y = 2 19 | uint8 CLIPPING_Z = 4 20 | 21 | uint8 accelerometer_clipping # bitfield indicating if there was any accelerometer clipping (per axis) during the integration time frame 22 | uint8 gyro_clipping # bitfield indicating if there was any gyro clipping (per axis) during the integration time frame 23 | 24 | uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes. 25 | uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes. 26 | -------------------------------------------------------------------------------- /msg/SensorCorrection.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor corrections in SI-unit form for the voted sensor 3 | # 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | # Corrections for acceleromter acceleration outputs where corrected_accel = raw_accel * accel_scale + accel_offset 8 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 9 | uint32[4] accel_device_ids 10 | float32[4] accel_temperature 11 | float32[3] accel_offset_0 # accelerometer 0 offsets in the FRD board frame XYZ-axis in m/s^s 12 | float32[3] accel_offset_1 # accelerometer 1 offsets in the FRD board frame XYZ-axis in m/s^s 13 | float32[3] accel_offset_2 # accelerometer 2 offsets in the FRD board frame XYZ-axis in m/s^s 14 | float32[3] accel_offset_3 # accelerometer 3 offsets in the FRD board frame XYZ-axis in m/s^s 15 | 16 | # Corrections for gyro angular rate outputs where corrected_rate = raw_rate * gyro_scale + gyro_offset 17 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 18 | uint32[4] gyro_device_ids 19 | float32[4] gyro_temperature 20 | float32[3] gyro_offset_0 # gyro 0 XYZ offsets in the sensor frame in rad/s 21 | float32[3] gyro_offset_1 # gyro 1 XYZ offsets in the sensor frame in rad/s 22 | float32[3] gyro_offset_2 # gyro 2 XYZ offsets in the sensor frame in rad/s 23 | float32[3] gyro_offset_3 # gyro 3 XYZ offsets in the sensor frame in rad/s 24 | 25 | # Corrections for magnetometer measurement outputs where corrected_mag = raw_mag * mag_scale + mag_offset 26 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 27 | uint32[4] mag_device_ids 28 | float32[4] mag_temperature 29 | float32[3] mag_offset_0 # magnetometer 0 offsets in the FRD board frame XYZ-axis in m/s^s 30 | float32[3] mag_offset_1 # magnetometer 1 offsets in the FRD board frame XYZ-axis in m/s^s 31 | float32[3] mag_offset_2 # magnetometer 2 offsets in the FRD board frame XYZ-axis in m/s^s 32 | float32[3] mag_offset_3 # magnetometer 3 offsets in the FRD board frame XYZ-axis in m/s^s 33 | 34 | # Corrections for barometric pressure outputs where corrected_pressure = raw_pressure * pressure_scale + pressure_offset 35 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 36 | uint32[4] baro_device_ids 37 | float32[4] baro_temperature 38 | float32 baro_offset_0 # barometric pressure 0 offsets in the sensor frame in Pascals 39 | float32 baro_offset_1 # barometric pressure 1 offsets in the sensor frame in Pascals 40 | float32 baro_offset_2 # barometric pressure 2 offsets in the sensor frame in Pascals 41 | float32 baro_offset_3 # barometric pressure 3 offsets in the sensor frame in Pascals 42 | -------------------------------------------------------------------------------- /msg/SensorGnssRelative.msg: -------------------------------------------------------------------------------- 1 | # GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint64 timestamp_sample # time since system start (microseconds) 5 | 6 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 7 | 8 | uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 9 | 10 | uint16 reference_station_id # Reference Station ID 11 | 12 | float32[3] position # GPS NED relative position vector (m) 13 | float32[3] position_accuracy # Accuracy of relative position (m) 14 | 15 | float32 heading # Heading of the relative position vector (radians) 16 | float32 heading_accuracy # Accuracy of heading of the relative position vector (radians) 17 | 18 | float32 position_length # Length of the position vector (m) 19 | float32 accuracy_length # Accuracy of the position length (m) 20 | 21 | bool gnss_fix_ok # GNSS valid fix (i.e within DOP & accuracy masks) 22 | bool differential_solution # differential corrections were applied 23 | bool relative_position_valid 24 | bool carrier_solution_floating # carrier phase range solution with floating ambiguities 25 | bool carrier_solution_fixed # carrier phase range solution with fixed ambiguities 26 | bool moving_base_mode # if the receiver is operating in moving base mode 27 | bool reference_position_miss # extrapolated reference position was used to compute moving base solution this epoch 28 | bool reference_observations_miss # extrapolated reference observations were used to compute moving base solution this epoch 29 | bool heading_valid 30 | bool relative_position_normalized # the components of the relative position vector (including the high-precision parts) are normalized 31 | -------------------------------------------------------------------------------- /msg/SensorGps.msg: -------------------------------------------------------------------------------- 1 | # GPS position in WGS84 coordinates. 2 | # the field 'timestamp' is for the position & velocity (microseconds) 3 | uint64 timestamp # time since system start (microseconds) 4 | uint64 timestamp_sample 5 | 6 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 7 | 8 | float64 latitude_deg # Latitude in degrees, allows centimeter level RTK precision 9 | float64 longitude_deg # Longitude in degrees, allows centimeter level RTK precision 10 | float64 altitude_msl_m # Altitude above MSL, meters 11 | float64 altitude_ellipsoid_m # Altitude above Ellipsoid, meters 12 | 13 | float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec) 14 | float32 c_variance_rad # GPS course accuracy estimate, (radians) 15 | uint8 FIX_TYPE_NONE = 1 # Value 0 is also valid to represent no fix. 16 | uint8 FIX_TYPE_2D = 2 17 | uint8 FIX_TYPE_3D = 3 18 | uint8 FIX_TYPE_RTCM_CODE_DIFFERENTIAL = 4 19 | uint8 FIX_TYPE_RTK_FLOAT = 5 20 | uint8 FIX_TYPE_RTK_FIXED = 6 21 | uint8 FIX_TYPE_EXTRAPOLATED = 8 22 | uint8 fix_type # Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 23 | 24 | float32 eph # GPS horizontal position accuracy (metres) 25 | float32 epv # GPS vertical position accuracy (metres) 26 | 27 | float32 hdop # Horizontal dilution of precision 28 | float32 vdop # Vertical dilution of precision 29 | 30 | int32 noise_per_ms # GPS noise per millisecond 31 | uint16 automatic_gain_control # Automatic gain control monitor 32 | 33 | uint8 JAMMING_STATE_UNKNOWN = 0 34 | uint8 JAMMING_STATE_OK = 1 35 | uint8 JAMMING_STATE_WARNING = 2 36 | uint8 JAMMING_STATE_CRITICAL = 3 37 | uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical 38 | int32 jamming_indicator # indicates jamming is occurring 39 | 40 | uint8 SPOOFING_STATE_UNKNOWN = 0 41 | uint8 SPOOFING_STATE_NONE = 1 42 | uint8 SPOOFING_STATE_INDICATED = 2 43 | uint8 SPOOFING_STATE_MULTIPLE = 3 44 | uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical 45 | 46 | float32 vel_m_s # GPS ground speed, (metres/sec) 47 | float32 vel_n_m_s # GPS North velocity, (metres/sec) 48 | float32 vel_e_m_s # GPS East velocity, (metres/sec) 49 | float32 vel_d_m_s # GPS Down velocity, (metres/sec) 50 | float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians) 51 | bool vel_ned_valid # True if NED velocity is valid 52 | 53 | int32 timestamp_time_relative # timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds) 54 | uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 55 | 56 | uint8 satellites_used # Number of satellites used 57 | 58 | float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) 59 | float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) 60 | float32 heading_accuracy # heading accuracy (rad, [0, 2PI]) 61 | 62 | float32 rtcm_injection_rate # RTCM message injection rate Hz 63 | uint8 selected_rtcm_instance # uorb instance that is being used for RTCM corrections 64 | 65 | bool rtcm_crc_failed # RTCM message CRC failure detected 66 | 67 | uint8 RTCM_MSG_USED_UNKNOWN = 0 68 | uint8 RTCM_MSG_USED_NOT_USED = 1 69 | uint8 RTCM_MSG_USED_USED = 2 70 | uint8 rtcm_msg_used # Indicates if the RTCM message was used successfully by the receiver 71 | 72 | # TOPICS sensor_gps vehicle_gps_position 73 | -------------------------------------------------------------------------------- /msg/SensorGyro.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 x # angular velocity in the FRD board frame X-axis in rad/s 7 | float32 y # angular velocity in the FRD board frame Y-axis in rad/s 8 | float32 z # angular velocity in the FRD board frame Z-axis in rad/s 9 | 10 | float32 temperature # temperature in degrees Celsius 11 | 12 | uint32 error_count 13 | 14 | uint8[3] clip_counter # clip count per axis in the sample period 15 | 16 | uint8 samples # number of raw samples that went into this message 17 | 18 | uint8 ORB_QUEUE_LENGTH = 8 19 | -------------------------------------------------------------------------------- /msg/SensorGyroFft.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 sensor_sample_rate_hz 7 | float32 resolution_hz 8 | 9 | float32[3] peak_frequencies_x # x axis peak frequencies 10 | float32[3] peak_frequencies_y # y axis peak frequencies 11 | float32[3] peak_frequencies_z # z axis peak frequencies 12 | 13 | float32[3] peak_snr_x # x axis peak SNR 14 | float32[3] peak_snr_y # y axis peak SNR 15 | float32[3] peak_snr_z # z axis peak SNR 16 | -------------------------------------------------------------------------------- /msg/SensorGyroFifo.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 dt # delta time between samples (microseconds) 7 | float32 scale 8 | 9 | uint8 samples # number of valid samples 10 | 11 | int16[32] x # angular velocity in the FRD board frame X-axis in rad/s 12 | int16[32] y # angular velocity in the FRD board frame Y-axis in rad/s 13 | int16[32] z # angular velocity in the FRD board frame Z-axis in rad/s 14 | 15 | uint8 ORB_QUEUE_LENGTH = 4 16 | -------------------------------------------------------------------------------- /msg/SensorHygrometer.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 temperature # Temperature provided by sensor (Celsius) 7 | 8 | float32 humidity # Humidity provided by sensor 9 | -------------------------------------------------------------------------------- /msg/SensorMag.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32 x # magnetic field in the FRD board frame X-axis in Gauss 7 | float32 y # magnetic field in the FRD board frame Y-axis in Gauss 8 | float32 z # magnetic field in the FRD board frame Z-axis in Gauss 9 | 10 | float32 temperature # temperature in degrees Celsius 11 | 12 | uint32 error_count 13 | 14 | uint8 ORB_QUEUE_LENGTH = 4 15 | -------------------------------------------------------------------------------- /msg/SensorOpticalFlow.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample 3 | 4 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | float32[2] pixel_flow # (radians) optical flow in radians where a positive value is produced by a RH rotation of the sensor about the body axis 7 | 8 | float32[3] delta_angle # (radians) accumulated gyro radians where a positive value is produced by a RH rotation about the body axis. Set to NaN if flow sensor does not have 3-axis gyro data. 9 | bool delta_angle_available 10 | 11 | float32 distance_m # (meters) Distance to the center of the flow field 12 | bool distance_available 13 | 14 | uint32 integration_timespan_us # (microseconds) accumulation timespan in microseconds 15 | 16 | uint8 quality # quality, 0: bad quality, 255: maximum quality 17 | 18 | uint32 error_count 19 | 20 | float32 max_flow_rate # (radians/s) Magnitude of maximum angular which the optical flow sensor can measure reliably 21 | 22 | float32 min_ground_distance # (meters) Minimum distance from ground at which the optical flow sensor operates reliably 23 | float32 max_ground_distance # (meters) Maximum distance from ground at which the optical flow sensor operates reliably 24 | 25 | uint8 MODE_UNKNOWN = 0 26 | uint8 MODE_BRIGHT = 1 27 | uint8 MODE_LOWLIGHT = 2 28 | uint8 MODE_SUPER_LOWLIGHT = 3 29 | 30 | uint8 mode 31 | -------------------------------------------------------------------------------- /msg/SensorPreflightMag.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Pre-flight sensor check metrics. 3 | # The topic will not be updated when the vehicle is armed 4 | # 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | float32 mag_inconsistency_angle # maximum angle between magnetometer instance field vectors in radians. 8 | -------------------------------------------------------------------------------- /msg/SensorSelection.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor ID's for the voted sensors output on the sensor_combined topic. 3 | # Will be updated on startup of the sensor module and when sensor selection changes 4 | # 5 | uint64 timestamp # time since system start (microseconds) 6 | uint32 accel_device_id # unique device ID for the selected accelerometers 7 | uint32 gyro_device_id # unique device ID for the selected rate gyros 8 | -------------------------------------------------------------------------------- /msg/SensorUwb.msg: -------------------------------------------------------------------------------- 1 | # UWB distance contains the distance information measured by an ultra-wideband positioning system, 2 | # such as Pozyx or NXP Rddrone. 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | uint32 sessionid # UWB SessionID 7 | uint32 time_offset # Time between Ranging Rounds in ms 8 | uint32 counter # Number of Ranges since last Start of Ranging 9 | uint16 mac # MAC adress of Initiator (controller) 10 | 11 | uint16 mac_dest # MAC adress of Responder (Controlee) 12 | uint16 status # status feedback # 13 | uint8 nlos # None line of site condition y/n 14 | float32 distance # distance in m to the UWB receiver 15 | 16 | 17 | #Angle of arrival, Angle in Degree -60..+60; FOV in both axis is 120 degrees 18 | float32 aoa_azimuth_dev # Angle of arrival of first incomming RX msg 19 | float32 aoa_elevation_dev # Angle of arrival of first incomming RX msg 20 | float32 aoa_azimuth_resp # Angle of arrival of first incomming RX msg at the responder 21 | float32 aoa_elevation_resp # Angle of arrival of first incomming RX msg at the responder 22 | 23 | # Figure of merit for the angle measurements 24 | uint8 aoa_azimuth_fom # AOA Azimuth FOM 25 | uint8 aoa_elevation_fom # AOA Elevation FOM 26 | uint8 aoa_dest_azimuth_fom # AOA Azimuth FOM 27 | uint8 aoa_dest_elevation_fom # AOA Elevation FOM 28 | 29 | # Initiator physical configuration 30 | uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum 31 | # Standard configuration is Antennas facing down and azimuth aligened in forward direction 32 | float32 offset_x # UWB initiator offset in X axis (NED drone frame) 33 | float32 offset_y # UWB initiator offset in Y axis (NED drone frame) 34 | float32 offset_z # UWB initiator offset in Z axis (NED drone frame) 35 | -------------------------------------------------------------------------------- /msg/SensorsStatus.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. 3 | # 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | uint32 device_id_primary # current primary device id for reference 7 | 8 | uint32[4] device_ids 9 | float32[4] inconsistency # magnitude of difference between sensor instance and mean 10 | bool[4] healthy # sensor healthy 11 | uint8[4] priority 12 | bool[4] enabled 13 | bool[4] external 14 | 15 | # TOPICS sensors_status_baro sensors_status_mag 16 | -------------------------------------------------------------------------------- /msg/SensorsStatusImu.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. 3 | # 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | uint32 accel_device_id_primary # current primary accel device id for reference 7 | 8 | uint32[4] accel_device_ids 9 | float32[4] accel_inconsistency_m_s_s # magnitude of acceleration difference between IMU instance and mean in m/s^2. 10 | bool[4] accel_healthy 11 | uint8[4] accel_priority 12 | 13 | uint32 gyro_device_id_primary # current primary gyro device id for reference 14 | 15 | uint32[4] gyro_device_ids 16 | float32[4] gyro_inconsistency_rad_s # magnitude of angular rate difference between IMU instance and mean in (rad/s). 17 | bool[4] gyro_healthy 18 | uint8[4] gyro_priority 19 | -------------------------------------------------------------------------------- /msg/SystemPower.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | float32 voltage5v_v # peripheral 5V rail voltage 3 | float32 voltage_payload_v # payload rail voltage 4 | float32[4] sensors3v3 # Sensors 3V3 rail voltage 5 | uint8 sensors3v3_valid # Sensors 3V3 rail voltage was read (bitfield). 6 | uint8 usb_connected # USB is connected when 1 7 | uint8 brick_valid # brick bits power is good when bit 1 8 | uint8 usb_valid # USB is valid when 1 9 | uint8 servo_valid # servo power is good when 1 10 | uint8 periph_5v_oc # peripheral overcurrent when 1 11 | uint8 hipower_5v_oc # high power peripheral overcurrent when 1 12 | uint8 comp_5v_valid # 5V to companion valid 13 | uint8 can1_gps1_5v_valid # 5V for CAN1/GPS1 valid 14 | uint8 payload_v_valid # payload rail voltage is valid 15 | 16 | uint8 BRICK1_VALID_SHIFTS=0 17 | uint8 BRICK1_VALID_MASK=1 18 | uint8 BRICK2_VALID_SHIFTS=1 19 | uint8 BRICK2_VALID_MASK=2 20 | uint8 BRICK3_VALID_SHIFTS=2 21 | uint8 BRICK3_VALID_MASK=4 22 | uint8 BRICK4_VALID_SHIFTS=3 23 | uint8 BRICK4_VALID_MASK=8 24 | -------------------------------------------------------------------------------- /msg/TakeoffStatus.msg: -------------------------------------------------------------------------------- 1 | # Status of the takeoff state machine currently just available for multicopters 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 TAKEOFF_STATE_UNINITIALIZED = 0 6 | uint8 TAKEOFF_STATE_DISARMED = 1 7 | uint8 TAKEOFF_STATE_SPOOLUP = 2 8 | uint8 TAKEOFF_STATE_READY_FOR_TAKEOFF = 3 9 | uint8 TAKEOFF_STATE_RAMPUP = 4 10 | uint8 TAKEOFF_STATE_FLIGHT = 5 11 | 12 | uint8 takeoff_state 13 | 14 | float32 tilt_limit # limited tilt feasibility during takeoff, contains maximum tilt otherwise 15 | -------------------------------------------------------------------------------- /msg/TaskStackInfo.msg: -------------------------------------------------------------------------------- 1 | # stack information for a single running process 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint16 stack_free 6 | char[24] task_name 7 | 8 | uint8 ORB_QUEUE_LENGTH = 2 9 | -------------------------------------------------------------------------------- /msg/TecsStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 altitude_sp # Altitude setpoint AMSL [m] 4 | float32 altitude_reference # Altitude setpoint reference AMSL [m] 5 | float32 altitude_time_constant # Time constant of the altitude tracker [s] 6 | float32 height_rate_reference # Height rate setpoint reference [m/s] 7 | float32 height_rate_direct # Direct height rate setpoint from velocity reference generator [m/s] 8 | float32 height_rate_setpoint # Height rate setpoint [m/s] 9 | float32 height_rate # Height rate [m/s] 10 | float32 equivalent_airspeed_sp # Equivalent airspeed setpoint [m/s] 11 | float32 true_airspeed_sp # True airspeed setpoint [m/s] 12 | float32 true_airspeed_filtered # True airspeed filtered [m/s] 13 | float32 true_airspeed_derivative_sp # True airspeed derivative setpoint [m/s^2] 14 | float32 true_airspeed_derivative # True airspeed derivative [m/s^2] 15 | float32 true_airspeed_derivative_raw # True airspeed derivative raw [m/s^2] 16 | 17 | float32 total_energy_rate_sp # Total energy rate setpoint [m^2/s^3] 18 | float32 total_energy_rate # Total energy rate estimate [m^2/s^3] 19 | 20 | float32 total_energy_balance_rate_sp # Energy balance rate setpoint [m^2/s^3] 21 | float32 total_energy_balance_rate # Energy balance rate estimate [m^2/s^3] 22 | 23 | float32 throttle_integ # Throttle integrator value [-] 24 | float32 pitch_integ # Pitch integrator value [rad] 25 | 26 | float32 throttle_sp # Current throttle setpoint [-] 27 | float32 pitch_sp_rad # Current pitch setpoint [rad] 28 | float32 throttle_trim # estimated throttle value [0,1] required to fly level at equivalent_airspeed_sp in the current atmospheric conditions 29 | 30 | float32 underspeed_ratio # 0: no underspeed, 1: maximal underspeed. Controller takes measures to avoid stall proportional to ratio if >0. 31 | float32 fast_descend_ratio # value indicating if fast descend mode is enabled with ramp up and ramp down [0-1] 32 | -------------------------------------------------------------------------------- /msg/TelemetryStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 LINK_TYPE_GENERIC = 0 2 | uint8 LINK_TYPE_UBIQUITY_BULLET = 1 3 | uint8 LINK_TYPE_WIRE = 2 4 | uint8 LINK_TYPE_USB = 3 5 | uint8 LINK_TYPE_IRIDIUM = 4 6 | 7 | uint64 timestamp # time since system start (microseconds) 8 | 9 | uint8 type # type of the radio hardware (LINK_TYPE_*) 10 | 11 | uint8 mode 12 | 13 | bool flow_control 14 | bool forwarding 15 | bool mavlink_v2 16 | bool ftp 17 | 18 | uint8 streams 19 | 20 | float32 data_rate # configured maximum data rate (Bytes/s) 21 | 22 | float32 rate_multiplier 23 | 24 | float32 tx_rate_avg # transmit rate average (Bytes/s) 25 | float32 tx_error_rate_avg # transmit error rate average (Bytes/s) 26 | uint32 tx_message_count # total message sent count 27 | uint32 tx_buffer_overruns # number of TX buffer overruns 28 | 29 | float32 rx_rate_avg # transmit rate average (Bytes/s) 30 | uint32 rx_message_count # count of total messages received 31 | uint32 rx_message_lost_count 32 | uint32 rx_buffer_overruns # number of RX buffer overruns 33 | uint32 rx_parse_errors # number of parse errors 34 | uint32 rx_packet_drop_count # number of packet drops 35 | float32 rx_message_lost_rate 36 | 37 | 38 | uint64 HEARTBEAT_TIMEOUT_US = 2500000 # Heartbeat timeout (tolerate missing 1 + jitter) 39 | 40 | # Heartbeats per type 41 | bool heartbeat_type_antenna_tracker # MAV_TYPE_ANTENNA_TRACKER 42 | bool heartbeat_type_gcs # MAV_TYPE_GCS 43 | bool heartbeat_type_onboard_controller # MAV_TYPE_ONBOARD_CONTROLLER 44 | bool heartbeat_type_gimbal # MAV_TYPE_GIMBAL 45 | bool heartbeat_type_adsb # MAV_TYPE_ADSB 46 | bool heartbeat_type_camera # MAV_TYPE_CAMERA 47 | bool heartbeat_type_parachute # MAV_TYPE_PARACHUTE 48 | bool heartbeat_type_open_drone_id # MAV_TYPE_ODID 49 | 50 | # Heartbeats per component 51 | bool heartbeat_component_telemetry_radio # MAV_COMP_ID_TELEMETRY_RADIO 52 | bool heartbeat_component_log # MAV_COMP_ID_LOG 53 | bool heartbeat_component_osd # MAV_COMP_ID_OSD 54 | bool heartbeat_component_vio # MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY 55 | bool heartbeat_component_pairing_manager # MAV_COMP_ID_PAIRING_MANAGER 56 | bool heartbeat_component_udp_bridge # MAV_COMP_ID_UDP_BRIDGE 57 | bool heartbeat_component_uart_bridge # MAV_COMP_ID_UART_BRIDGE 58 | 59 | # Misc component health 60 | bool open_drone_id_system_healthy 61 | bool parachute_system_healthy 62 | -------------------------------------------------------------------------------- /msg/TiltrotorExtraControls.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | float32 collective_tilt_normalized_setpoint # Collective tilt angle of motors of tiltrotor, 0: vertical, 1: horizontal [0, 1] 4 | float32 collective_thrust_normalized_setpoint # Collective thrust setpoint [0, 1] 5 | -------------------------------------------------------------------------------- /msg/TimesyncStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint8 SOURCE_PROTOCOL_UNKNOWN = 0 4 | uint8 SOURCE_PROTOCOL_MAVLINK = 1 5 | uint8 SOURCE_PROTOCOL_DDS = 2 6 | uint8 source_protocol # timesync source 7 | 8 | uint64 remote_timestamp # remote system timestamp (microseconds) 9 | int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds) 10 | int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds) 11 | uint32 round_trip_time # round trip time of this timesync packet (microseconds) 12 | -------------------------------------------------------------------------------- /msg/TrajectorySetpoint.msg: -------------------------------------------------------------------------------- 1 | # Trajectory setpoint in NED frame 2 | # Input to PID position controller. 3 | # Needs to be kinematically consistent and feasible for smooth flight. 4 | # setting a value to NaN means the state should not be controlled 5 | 6 | uint32 MESSAGE_VERSION = 0 7 | 8 | uint64 timestamp # time since system start (microseconds) 9 | 10 | # NED local world frame 11 | float32[3] position # in meters 12 | float32[3] velocity # in meters/second 13 | float32[3] acceleration # in meters/second^2 14 | float32[3] jerk # in meters/second^3 (for logging only) 15 | 16 | float32 yaw # euler angle of desired attitude in radians -PI..+PI 17 | float32 yawspeed # angular velocity around NED frame z-axis in radians/second 18 | -------------------------------------------------------------------------------- /msg/TrajectorySetpoint6dof.msg: -------------------------------------------------------------------------------- 1 | # Trajectory setpoint in NED frame 2 | # Input to position controller. 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | # NED local world frame 7 | float32[3] position # in meters 8 | float32[3] velocity # in meters/second 9 | float32[3] acceleration # in meters/second^2 10 | float32[3] jerk # in meters/second^3 (for logging only) 11 | 12 | float32[4] quaternion # unit quaternion 13 | float32[3] angular_velocity # angular velocity in radians/second 14 | -------------------------------------------------------------------------------- /msg/TransponderReport.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint32 icao_address # ICAO address 3 | float64 lat # Latitude, expressed as degrees 4 | float64 lon # Longitude, expressed as degrees 5 | uint8 altitude_type # Type from ADSB_ALTITUDE_TYPE enum 6 | float32 altitude # Altitude(ASL) in meters 7 | float32 heading # Course over ground in radians, -pi to +pi, 0 is north 8 | float32 hor_velocity # The horizontal velocity in m/s 9 | float32 ver_velocity # The vertical velocity in m/s, positive is up 10 | char[9] callsign # The callsign, 8+null 11 | uint8 emitter_type # Type from ADSB_EMITTER_TYPE enum 12 | uint8 tslc # Time since last communication in seconds 13 | uint16 flags # Flags to indicate various statuses including valid data fields 14 | uint16 squawk # Squawk code 15 | uint8[18] uas_id # Unique UAS ID 16 | 17 | # ADSB flags 18 | uint16 PX4_ADSB_FLAGS_VALID_COORDS = 1 19 | uint16 PX4_ADSB_FLAGS_VALID_ALTITUDE = 2 20 | uint16 PX4_ADSB_FLAGS_VALID_HEADING = 4 21 | uint16 PX4_ADSB_FLAGS_VALID_VELOCITY = 8 22 | uint16 PX4_ADSB_FLAGS_VALID_CALLSIGN = 16 23 | uint16 PX4_ADSB_FLAGS_VALID_SQUAWK = 32 24 | uint16 PX4_ADSB_FLAGS_RETRANSLATE = 256 25 | 26 | #ADSB Emitter Data: 27 | #from mavlink/v2.0/common/common.h 28 | uint16 ADSB_EMITTER_TYPE_NO_INFO=0 29 | uint16 ADSB_EMITTER_TYPE_LIGHT=1 30 | uint16 ADSB_EMITTER_TYPE_SMALL=2 31 | uint16 ADSB_EMITTER_TYPE_LARGE=3 32 | uint16 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE=4 33 | uint16 ADSB_EMITTER_TYPE_HEAVY=5 34 | uint16 ADSB_EMITTER_TYPE_HIGHLY_MANUV=6 35 | uint16 ADSB_EMITTER_TYPE_ROTOCRAFT=7 36 | uint16 ADSB_EMITTER_TYPE_UNASSIGNED=8 37 | uint16 ADSB_EMITTER_TYPE_GLIDER=9 38 | uint16 ADSB_EMITTER_TYPE_LIGHTER_AIR=10 39 | uint16 ADSB_EMITTER_TYPE_PARACHUTE=11 40 | uint16 ADSB_EMITTER_TYPE_ULTRA_LIGHT=12 41 | uint16 ADSB_EMITTER_TYPE_UNASSIGNED2=13 42 | uint16 ADSB_EMITTER_TYPE_UAV=14 43 | uint16 ADSB_EMITTER_TYPE_SPACE=15 44 | uint16 ADSB_EMITTER_TYPE_UNASSGINED3=16 45 | uint16 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE=17 46 | uint16 ADSB_EMITTER_TYPE_SERVICE_SURFACE=18 47 | uint16 ADSB_EMITTER_TYPE_POINT_OBSTACLE=19 48 | uint16 ADSB_EMITTER_TYPE_ENUM_END=20 49 | 50 | uint8 ORB_QUEUE_LENGTH = 16 51 | -------------------------------------------------------------------------------- /msg/TuneControl.msg: -------------------------------------------------------------------------------- 1 | # This message is used to control the tunes, when the tune_id is set to CUSTOM 2 | # then the frequency, duration are used otherwise those values are ignored. 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | uint8 TUNE_ID_STOP = 0 7 | uint8 TUNE_ID_STARTUP = 1 8 | uint8 TUNE_ID_ERROR = 2 9 | uint8 TUNE_ID_NOTIFY_POSITIVE = 3 10 | uint8 TUNE_ID_NOTIFY_NEUTRAL = 4 11 | uint8 TUNE_ID_NOTIFY_NEGATIVE = 5 12 | uint8 TUNE_ID_ARMING_WARNING = 6 13 | uint8 TUNE_ID_BATTERY_WARNING_SLOW = 7 14 | uint8 TUNE_ID_BATTERY_WARNING_FAST = 8 15 | uint8 TUNE_ID_GPS_WARNING = 9 16 | uint8 TUNE_ID_ARMING_FAILURE = 10 17 | uint8 TUNE_ID_PARACHUTE_RELEASE = 11 18 | uint8 TUNE_ID_SINGLE_BEEP = 12 19 | uint8 TUNE_ID_HOME_SET = 13 20 | uint8 TUNE_ID_SD_INIT = 14 21 | uint8 TUNE_ID_SD_ERROR = 15 22 | uint8 TUNE_ID_PROG_PX4IO = 16 23 | uint8 TUNE_ID_PROG_PX4IO_OK = 17 24 | uint8 TUNE_ID_PROG_PX4IO_ERR = 18 25 | uint8 TUNE_ID_POWER_OFF = 19 26 | uint8 NUMBER_OF_TUNES = 20 27 | 28 | uint8 tune_id # tune_id corresponding to TuneID::* from the tune_defaults.h in the tunes library 29 | bool tune_override # if true the tune which is playing will be stopped and the new started 30 | uint16 frequency # in Hz 31 | uint32 duration # in us 32 | uint32 silence # in us 33 | uint8 volume # value between 0-100 if supported by backend 34 | 35 | uint8 VOLUME_LEVEL_MIN = 0 36 | uint8 VOLUME_LEVEL_DEFAULT = 20 37 | uint8 VOLUME_LEVEL_MAX = 100 38 | 39 | uint8 ORB_QUEUE_LENGTH = 4 40 | -------------------------------------------------------------------------------- /msg/UavcanParameterRequest.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge request type 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint8 MESSAGE_TYPE_PARAM_REQUEST_READ = 20 # MAVLINK_MSG_ID_PARAM_REQUEST_READ 5 | uint8 MESSAGE_TYPE_PARAM_REQUEST_LIST = 21 # MAVLINK_MSG_ID_PARAM_REQUEST_LIST 6 | uint8 MESSAGE_TYPE_PARAM_SET = 23 # MAVLINK_MSG_ID_PARAM_SET 7 | uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET 8 | 9 | uint8 NODE_ID_ALL = 0 # MAV_COMP_ID_ALL 10 | uint8 node_id # UAVCAN node ID mapped from MAVLink component ID 11 | 12 | char[17] param_id # MAVLink/UAVCAN parameter name 13 | int16 param_index # -1 if the param_id field should be used as identifier 14 | 15 | uint8 PARAM_TYPE_UINT8 = 1 # MAV_PARAM_TYPE_UINT8 16 | uint8 PARAM_TYPE_INT64 = 8 # MAV_PARAM_TYPE_INT64 17 | uint8 PARAM_TYPE_REAL32 = 9 # MAV_PARAM_TYPE_REAL32 18 | uint8 param_type # MAVLink parameter type 19 | 20 | int64 int_value # current value if param_type is int-like 21 | float32 real_value # current value if param_type is float-like 22 | 23 | uint8 ORB_QUEUE_LENGTH = 4 24 | -------------------------------------------------------------------------------- /msg/UavcanParameterValue.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge response type 2 | uint64 timestamp # time since system start (microseconds) 3 | uint8 node_id # UAVCAN node ID mapped from MAVLink component ID 4 | char[17] param_id # MAVLink/UAVCAN parameter name 5 | int16 param_index # parameter index, if known 6 | uint16 param_count # number of parameters exposed by the node 7 | uint8 param_type # MAVLink parameter type 8 | int64 int_value # current value if param_type is int-like 9 | float32 real_value # current value if param_type is float-like 10 | -------------------------------------------------------------------------------- /msg/UlogStream.msg: -------------------------------------------------------------------------------- 1 | # Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA 2 | # mavlink message 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | # flags bitmasks 7 | uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked. 8 | # Acked messages are published synchronous: a 9 | # publisher waits for an ack before sending the 10 | # next message 11 | 12 | uint8 length # length of data 13 | uint8 first_message_offset # offset into data where first message starts. This 14 | # can be used for recovery, when a previous message got lost 15 | uint16 msg_sequence # allows determine drops 16 | uint8 flags # see FLAGS_* 17 | uint8[249] data # ulog data 18 | 19 | uint8 ORB_QUEUE_LENGTH = 16 # TODO: we might be able to reduce this if mavlink polled on the topic 20 | -------------------------------------------------------------------------------- /msg/UlogStreamAck.msg: -------------------------------------------------------------------------------- 1 | # Ack a previously sent ulog_stream message that had 2 | # the NEED_ACK flag set 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms] 6 | int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms 7 | 8 | uint16 msg_sequence 9 | -------------------------------------------------------------------------------- /msg/UnregisterExtComponent.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | char[25] name # either the mode name, or component name 6 | 7 | int8 arming_check_id # arming check registration ID (-1 if not registered) 8 | int8 mode_id # assigned mode ID (-1 if not registered) 9 | int8 mode_executor_id # assigned mode executor ID (-1 if not registered) 10 | -------------------------------------------------------------------------------- /msg/VehicleAcceleration.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 5 | 6 | float32[3] xyz # Bias corrected acceleration (including gravity) in the FRD body frame XYZ-axis in m/s^2 7 | -------------------------------------------------------------------------------- /msg/VehicleAirData.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 5 | 6 | uint32 baro_device_id # unique device ID for the selected barometer 7 | 8 | float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH. 9 | float32 baro_pressure_pa # Absolute pressure in Pascals 10 | float32 ambient_temperature # Abient temperature in degrees Celsius 11 | uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed 12 | 13 | float32 rho # air density 14 | 15 | uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. 16 | -------------------------------------------------------------------------------- /msg/VehicleAngularAccelerationSetpoint.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) 4 | 5 | float32[3] xyz # angular acceleration about X, Y, Z body axis in rad/s^2 6 | -------------------------------------------------------------------------------- /msg/VehicleAngularVelocity.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) 5 | 6 | float32[3] xyz # Bias corrected angular velocity about the FRD body frame XYZ-axis in rad/s 7 | 8 | float32[3] xyz_derivative # angular acceleration about the FRD body frame XYZ-axis in rad/s^2 9 | 10 | # TOPICS vehicle_angular_velocity vehicle_angular_velocity_groundtruth 11 | -------------------------------------------------------------------------------- /msg/VehicleAttitude.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use 2 | # The quaternion uses the Hamilton convention, and the order is q(w, x, y, z) 3 | 4 | uint32 MESSAGE_VERSION = 0 5 | 6 | uint64 timestamp # time since system start (microseconds) 7 | 8 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 9 | 10 | float32[4] q # Quaternion rotation from the FRD body frame to the NED earth frame 11 | float32[4] delta_q_reset # Amount by which quaternion has changed during last reset 12 | uint8 quat_reset_counter # Quaternion reset counter 13 | 14 | # TOPICS vehicle_attitude vehicle_attitude_groundtruth external_ins_attitude 15 | # TOPICS estimator_attitude 16 | -------------------------------------------------------------------------------- /msg/VehicleAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 1 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | float32 yaw_sp_move_rate # rad/s (commanded by user) 6 | 7 | # For quaternion-based attitude control 8 | float32[4] q_d # Desired quaternion for quaternion control 9 | 10 | # For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. 11 | # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. 12 | float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] 13 | 14 | # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 15 | -------------------------------------------------------------------------------- /msg/VehicleCommandAck.msg: -------------------------------------------------------------------------------- 1 | # Vehicle Command Ackonwledgement uORB message. 2 | # Used for acknowledging the vehicle command being received. 3 | # Follows the MAVLink COMMAND_ACK message definition 4 | 5 | uint32 MESSAGE_VERSION = 0 6 | 7 | uint64 timestamp # time since system start (microseconds) 8 | 9 | # Result cases. This follows the MAVLink MAV_RESULT enum definition 10 | uint8 VEHICLE_CMD_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED | 11 | uint8 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED | 12 | uint8 VEHICLE_CMD_RESULT_DENIED = 2 # Command PERMANENTLY DENIED | 13 | uint8 VEHICLE_CMD_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED | 14 | uint8 VEHICLE_CMD_RESULT_FAILED = 4 # Command executed, but failed | 15 | uint8 VEHICLE_CMD_RESULT_IN_PROGRESS = 5 # Command being executed | 16 | uint8 VEHICLE_CMD_RESULT_CANCELLED = 6 # Command Canceled 17 | 18 | # Arming denied specific cases 19 | uint16 ARM_AUTH_DENIED_REASON_GENERIC = 0 20 | uint16 ARM_AUTH_DENIED_REASON_NONE = 1 21 | uint16 ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2 22 | uint16 ARM_AUTH_DENIED_REASON_TIMEOUT = 3 23 | uint16 ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4 24 | uint16 ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5 25 | 26 | uint8 ORB_QUEUE_LENGTH = 4 27 | 28 | uint32 command # Command that is being acknowledged 29 | uint8 result # Command result 30 | uint8 result_param1 # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS 31 | int32 result_param2 # Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied. 32 | uint8 target_system 33 | uint16 target_component # Target component / mode executor 34 | 35 | bool from_external # Indicates if the command came from an external source 36 | -------------------------------------------------------------------------------- /msg/VehicleConstraints.msg: -------------------------------------------------------------------------------- 1 | # Local setpoint constraints in NED frame 2 | # setting something to NaN means that no limit is provided 3 | 4 | uint64 timestamp # time since system start (microseconds) 5 | 6 | float32 speed_up # in meters/sec 7 | float32 speed_down # in meters/sec 8 | 9 | bool want_takeoff # tell the controller to initiate takeoff when idling (ignored during flight) 10 | -------------------------------------------------------------------------------- /msg/VehicleControlMode.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | bool flag_armed # synonym for actuator_armed.armed 5 | 6 | bool flag_multicopter_position_control_enabled 7 | 8 | bool flag_control_manual_enabled # true if manual input is mixed in 9 | bool flag_control_auto_enabled # true if onboard autopilot should act 10 | bool flag_control_offboard_enabled # true if offboard control should be used 11 | bool flag_control_position_enabled # true if position is controlled 12 | bool flag_control_velocity_enabled # true if horizontal velocity (implies direction) is controlled 13 | bool flag_control_altitude_enabled # true if altitude is controlled 14 | bool flag_control_climb_rate_enabled # true if climb rate is controlled 15 | bool flag_control_acceleration_enabled # true if acceleration is controlled 16 | bool flag_control_attitude_enabled # true if attitude stabilization is mixed in 17 | bool flag_control_rates_enabled # true if rates are stabilized 18 | bool flag_control_allocation_enabled # true if control allocation is enabled 19 | bool flag_control_termination_enabled # true if flighttermination is enabled 20 | 21 | # TODO: use dedicated topic for external requests 22 | uint8 source_id # Mode ID (nav_state) 23 | 24 | # TOPICS vehicle_control_mode config_control_setpoints 25 | -------------------------------------------------------------------------------- /msg/VehicleGlobalPosition.msg: -------------------------------------------------------------------------------- 1 | # Fused global position in WGS84. 2 | # This struct contains global position estimation. It is not the raw GPS 3 | # measurement (@see vehicle_gps_position). This topic is usually published by the position 4 | # estimator, which will take more sources of information into account than just GPS, 5 | # e.g. control inputs of the vehicle in a Kalman-filter implementation. 6 | # 7 | 8 | uint32 MESSAGE_VERSION = 0 9 | 10 | uint64 timestamp # time since system start (microseconds) 11 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 12 | 13 | float64 lat # Latitude, (degrees) 14 | float64 lon # Longitude, (degrees) 15 | float32 alt # Altitude AMSL, (meters) 16 | float32 alt_ellipsoid # Altitude above ellipsoid, (meters) 17 | 18 | bool lat_lon_valid 19 | bool alt_valid 20 | 21 | float32 delta_alt # Reset delta for altitude 22 | float32 delta_terrain # Reset delta for terrain 23 | uint8 lat_lon_reset_counter # Counter for reset events on horizontal position coordinates 24 | uint8 alt_reset_counter # Counter for reset events on altitude 25 | uint8 terrain_reset_counter # Counter for reset events on terrain 26 | 27 | float32 eph # Standard deviation of horizontal position error, (metres) 28 | float32 epv # Standard deviation of vertical position error, (metres) 29 | 30 | float32 terrain_alt # Terrain altitude WGS84, (metres) 31 | bool terrain_alt_valid # Terrain altitude estimate is valid 32 | 33 | bool dead_reckoning # True if this position is estimated through dead-reckoning 34 | 35 | # TOPICS vehicle_global_position vehicle_global_position_groundtruth external_ins_global_position 36 | # TOPICS estimator_global_position 37 | # TOPICS aux_global_position 38 | -------------------------------------------------------------------------------- /msg/VehicleImu.msg: -------------------------------------------------------------------------------- 1 | # IMU readings in SI-unit form. 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint64 timestamp_sample 5 | 6 | uint32 accel_device_id # Accelerometer unique device ID for the sensor that does not change between power cycles 7 | uint32 gyro_device_id # Gyroscope unique device ID for the sensor that does not change between power cycles 8 | 9 | float32[3] delta_angle # delta angle about the FRD body frame XYZ-axis in rad over the integration time frame (delta_angle_dt) 10 | float32[3] delta_velocity # delta velocity in the FRD body frame XYZ-axis in m/s over the integration time frame (delta_velocity_dt) 11 | 12 | uint32 delta_angle_dt # integration period in microseconds 13 | uint32 delta_velocity_dt # integration period in microseconds 14 | 15 | uint8 CLIPPING_X = 1 16 | uint8 CLIPPING_Y = 2 17 | uint8 CLIPPING_Z = 4 18 | 19 | uint8 delta_angle_clipping # bitfield indicating if there was any gyro clipping (per axis) during the integration time frame 20 | uint8 delta_velocity_clipping # bitfield indicating if there was any accelerometer clipping (per axis) during the integration time frame 21 | 22 | uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes. 23 | uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes. 24 | -------------------------------------------------------------------------------- /msg/VehicleImuStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | uint32 accel_device_id # unique device ID for the sensor that does not change between power cycles 4 | uint32 gyro_device_id # unique device ID for the sensor that does not change between power cycles 5 | 6 | uint32[3] accel_clipping # total clipping per axis 7 | uint32[3] gyro_clipping # total clipping per axis 8 | 9 | uint32 accel_error_count 10 | uint32 gyro_error_count 11 | 12 | float32 accel_rate_hz 13 | float32 gyro_rate_hz 14 | 15 | float32 accel_raw_rate_hz # full raw sensor sample rate (Hz) 16 | float32 gyro_raw_rate_hz # full raw sensor sample rate (Hz) 17 | 18 | float32 accel_vibration_metric # high frequency vibration level in the accelerometer data (m/s/s) 19 | float32 gyro_vibration_metric # high frequency vibration level in the gyro data (rad/s) 20 | float32 delta_angle_coning_metric # average IMU delta angle coning correction (rad^2) 21 | 22 | float32[3] mean_accel # average accelerometer readings since last publication 23 | float32[3] mean_gyro # average gyroscope readings since last publication 24 | float32[3] var_accel # accelerometer variance since last publication 25 | float32[3] var_gyro # gyroscope variance since last publication 26 | 27 | float32 temperature_accel 28 | float32 temperature_gyro 29 | -------------------------------------------------------------------------------- /msg/VehicleLandDetected.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | bool freefall # true if vehicle is currently in free-fall 6 | bool ground_contact # true if vehicle has ground contact but is not landed (1. stage) 7 | bool maybe_landed # true if the vehicle might have landed (2. stage) 8 | bool landed # true if vehicle is currently landed on the ground (3. stage) 9 | 10 | bool in_ground_effect # indicates if from the perspective of the landing detector the vehicle might be in ground effect (baro). This flag will become true if the vehicle is not moving horizontally and is descending (crude assumption that user is landing). 11 | bool in_descend 12 | 13 | bool has_low_throttle 14 | 15 | bool vertical_movement 16 | bool horizontal_movement 17 | bool rotational_movement 18 | 19 | bool close_to_ground_or_skipped_check 20 | 21 | bool at_rest 22 | -------------------------------------------------------------------------------- /msg/VehicleLocalPositionSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Local position setpoint in NED frame 2 | # Telemetry of PID position controller to monitor tracking. 3 | # NaN means the state was not controlled 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | 7 | float32 x # in meters NED 8 | float32 y # in meters NED 9 | float32 z # in meters NED 10 | 11 | float32 vx # in meters/sec 12 | float32 vy # in meters/sec 13 | float32 vz # in meters/sec 14 | 15 | float32[3] acceleration # in meters/sec^2 16 | float32[3] thrust # normalized thrust vector in NED 17 | 18 | float32 yaw # in radians NED -PI..+PI 19 | float32 yawspeed # in radians/sec 20 | -------------------------------------------------------------------------------- /msg/VehicleMagnetometer.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | 4 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 5 | 6 | uint32 device_id # unique device ID for the selected magnetometer 7 | 8 | float32[3] magnetometer_ga # Magnetic field in the FRD body frame XYZ-axis in Gauss 9 | 10 | uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. 11 | -------------------------------------------------------------------------------- /msg/VehicleOdometry.msg: -------------------------------------------------------------------------------- 1 | # Vehicle odometry data. Fits ROS REP 147 for aerial vehicles 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint64 timestamp # time since system start (microseconds) 6 | uint64 timestamp_sample 7 | 8 | uint8 POSE_FRAME_UNKNOWN = 0 9 | uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame 10 | uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference 11 | uint8 pose_frame # Position and orientation frame of reference 12 | 13 | float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown 14 | float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown 15 | 16 | uint8 VELOCITY_FRAME_UNKNOWN = 0 17 | uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame 18 | uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference 19 | uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame 20 | uint8 velocity_frame # Reference frame of the velocity data 21 | 22 | float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown 23 | 24 | float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown 25 | 26 | float32[3] position_variance 27 | float32[3] orientation_variance 28 | float32[3] velocity_variance 29 | 30 | uint8 reset_counter 31 | int8 quality 32 | 33 | # TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry 34 | # TOPICS estimator_odometry 35 | -------------------------------------------------------------------------------- /msg/VehicleOpticalFlow.msg: -------------------------------------------------------------------------------- 1 | # Optical flow in XYZ body frame in SI units. 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | uint64 timestamp_sample 5 | 6 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 7 | 8 | float32[2] pixel_flow # (radians) accumulated optical flow in radians where a positive value is produced by a RH rotation about the body axis 9 | 10 | float32[3] delta_angle # (radians) accumulated gyro radians where a positive value is produced by a RH rotation of the sensor about the body axis. (NAN if unavailable) 11 | 12 | float32 distance_m # (meters) Distance to the center of the flow field (NAN if unavailable) 13 | 14 | uint32 integration_timespan_us # (microseconds) accumulation timespan in microseconds 15 | 16 | uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: maximum quality 17 | 18 | float32 max_flow_rate # (radians/s) Magnitude of maximum angular which the optical flow sensor can measure reliably 19 | 20 | float32 min_ground_distance # (meters) Minimum distance from ground at which the optical flow sensor operates reliably 21 | float32 max_ground_distance # (meters) Maximum distance from ground at which the optical flow sensor operates reliably 22 | -------------------------------------------------------------------------------- /msg/VehicleOpticalFlowVel.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | float32[2] vel_body # velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) 5 | float32[2] vel_ne # same as vel_body but in local frame (m/s) 6 | 7 | float32[2] vel_body_filtered # filtered velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) 8 | float32[2] vel_ne_filtered # filtered same as vel_body_filtered but in local frame (m/s) 9 | 10 | float32[2] flow_rate_uncompensated # integrated optical flow measurement (rad/s) 11 | float32[2] flow_rate_compensated # integrated optical flow measurement compensated for angular motion (rad/s) 12 | 13 | float32[3] gyro_rate # gyro measurement synchronized with flow measurements (rad/s) 14 | 15 | float32[3] gyro_bias 16 | float32[3] ref_gyro 17 | 18 | # TOPICS estimator_optical_flow_vel vehicle_optical_flow_vel 19 | -------------------------------------------------------------------------------- /msg/VehicleRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | uint32 MESSAGE_VERSION = 0 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | # body angular rates in FRD frame 6 | float32 roll # [rad/s] roll rate setpoint 7 | float32 pitch # [rad/s] pitch rate setpoint 8 | float32 yaw # [rad/s] yaw rate setpoint 9 | 10 | # For clarification: For multicopters thrust_body[0] and thrust[1] are usually 0 and thrust[2] is the negative throttle demand. 11 | # For fixed wings thrust_x is the throttle demand and thrust_y, thrust_z will usually be zero. 12 | float32[3] thrust_body # Normalized thrust command in body NED frame [-1,1] 13 | 14 | bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) 15 | -------------------------------------------------------------------------------- /msg/VehicleRoi.msg: -------------------------------------------------------------------------------- 1 | # Vehicle Region Of Interest (ROI) 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | uint8 ROI_NONE = 0 # No region of interest 6 | uint8 ROI_WPNEXT = 1 # Point toward next MISSION with optional offset 7 | uint8 ROI_WPINDEX = 2 # Point toward given MISSION 8 | uint8 ROI_LOCATION = 3 # Point toward fixed location 9 | uint8 ROI_TARGET = 4 # Point toward target 10 | uint8 ROI_ENUM_END = 5 11 | 12 | uint8 mode # ROI mode (see above) 13 | 14 | float64 lat # Latitude to point to 15 | float64 lon # Longitude to point to 16 | float32 alt # Altitude to point to 17 | 18 | # additional angle offsets to next waypoint (only used with ROI_WPNEXT) 19 | float32 roll_offset # angle offset in rad 20 | float32 pitch_offset # angle offset in rad 21 | float32 yaw_offset # angle offset in rad 22 | -------------------------------------------------------------------------------- /msg/VehicleThrustSetpoint.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) 4 | 5 | float32[3] xyz # thrust setpoint along X, Y, Z body axis [-1, 1] 6 | 7 | # TOPICS vehicle_thrust_setpoint 8 | # TOPICS vehicle_thrust_setpoint_virtual_fw vehicle_thrust_setpoint_virtual_mc 9 | -------------------------------------------------------------------------------- /msg/VehicleTorqueSetpoint.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 timestamp # time since system start (microseconds) 3 | uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) 4 | 5 | float32[3] xyz # torque setpoint about X, Y, Z body axis (normalized) 6 | 7 | # TOPICS vehicle_torque_setpoint 8 | # TOPICS vehicle_torque_setpoint_virtual_fw vehicle_torque_setpoint_virtual_mc 9 | -------------------------------------------------------------------------------- /msg/VelocityLimits.msg: -------------------------------------------------------------------------------- 1 | # Velocity and yaw rate limits for a multicopter position slow mode only 2 | 3 | uint64 timestamp # time since system start (microseconds) 4 | 5 | # absolute speeds, NAN means use default limit 6 | float32 horizontal_velocity # [m/s] 7 | float32 vertical_velocity # [m/s] 8 | float32 yaw_rate # [rad/s] 9 | -------------------------------------------------------------------------------- /msg/VtolVehicleStatus.msg: -------------------------------------------------------------------------------- 1 | # VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE 2 | 3 | uint32 MESSAGE_VERSION = 0 4 | 5 | uint8 VEHICLE_VTOL_STATE_UNDEFINED = 0 6 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_FW = 1 7 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2 8 | uint8 VEHICLE_VTOL_STATE_MC = 3 9 | uint8 VEHICLE_VTOL_STATE_FW = 4 10 | 11 | uint64 timestamp # time since system start (microseconds) 12 | 13 | uint8 vehicle_vtol_state # current state of the vtol, see VEHICLE_VTOL_STATE 14 | 15 | bool fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) 16 | -------------------------------------------------------------------------------- /msg/WheelEncoders.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | 3 | # Two wheels: 0 right, 1 left 4 | float32[2] wheel_speed # [rad/s] 5 | float32[2] wheel_angle # [rad] 6 | -------------------------------------------------------------------------------- /msg/Wind.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | float32 windspeed_north # Wind component in north / X direction (m/sec) 5 | float32 windspeed_east # Wind component in east / Y direction (m/sec) 6 | 7 | float32 variance_north # Wind estimate error variance in north / X direction (m/sec)**2 - set to zero (no uncertainty) if not estimated 8 | float32 variance_east # Wind estimate error variance in east / Y direction (m/sec)**2 - set to zero (no uncertainty) if not estimated 9 | 10 | float32 tas_innov # True airspeed innovation 11 | float32 tas_innov_var # True airspeed innovation variance 12 | 13 | float32 beta_innov # Sideslip measurement innovation 14 | float32 beta_innov_var # Sideslip measurement innovation variance 15 | 16 | # TOPICS wind estimator_wind 17 | -------------------------------------------------------------------------------- /msg/YawEstimatorStatus.msg: -------------------------------------------------------------------------------- 1 | uint64 timestamp # time since system start (microseconds) 2 | uint64 timestamp_sample # the timestamp of the raw data (microseconds) 3 | 4 | float32 yaw_composite # composite yaw from GSF (rad) 5 | float32 yaw_variance # composite yaw variance from GSF (rad^2) 6 | bool yaw_composite_valid 7 | 8 | float32[5] yaw # yaw estimate for each model in the filter bank (rad) 9 | float32[5] innov_vn # North velocity innovation for each model in the filter bank (m/s) 10 | float32[5] innov_ve # East velocity innovation for each model in the filter bank (m/s) 11 | float32[5] weight # weighting for each model in the filter bank 12 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | px4_msgs 5 | 2.0.1 6 | Package with the ROS-equivalent of PX4 uORB msgs 7 | Nuno Marques 8 | Nuno Marques 9 | BSD 3-Clause 10 | 11 | ament_cmake 12 | rosidl_default_generators 13 | 14 | builtin_interfaces 15 | ros_environment 16 | 17 | rosidl_default_runtime 18 | 19 | ament_lint_common 20 | 21 | rosidl_interface_packages 22 | 23 | 24 | ament_cmake 25 | 26 | 27 | -------------------------------------------------------------------------------- /srv/VehicleCommand.srv: -------------------------------------------------------------------------------- 1 | VehicleCommand request 2 | --- 3 | VehicleCommandAck reply 4 | --------------------------------------------------------------------------------