├── LICENSE ├── README.rst ├── doc ├── PX4-to-ros.png └── complete_loop.png ├── micrortps_agent ├── CMakeLists.txt ├── UART_node.cxx ├── UART_node.h ├── microRTPS_agent.cxx ├── sensor_combined_.cxx ├── sensor_combined_.h ├── sensor_combined_PubSubTypes.cxx ├── sensor_combined_PubSubTypes.h ├── sensor_combined_Publisher.cxx ├── sensor_combined_Publisher.h ├── sensor_combined_Subscriber.cxx └── sensor_combined_Subscriber.h ├── micrortps_client ├── CMakeLists.txt ├── UART_node.cxx ├── UART_node.h └── microRTPS_client.cpp ├── px4_msgs_ros1 ├── CMakeLists.txt ├── msg │ ├── ActuatorArmed.msg │ ├── ActuatorControls.msg │ ├── ActuatorDirect.msg │ ├── ActuatorOutputs.msg │ ├── AdcReport.msg │ ├── Airspeed.msg │ ├── AttPosMocap.msg │ ├── BatteryStatus.msg │ ├── CameraTrigger.msg │ ├── CollisionReport.msg │ ├── CommanderState.msg │ ├── ControlState.msg │ ├── Cpuload.msg │ ├── DebugKeyValue.msg │ ├── DifferentialPressure.msg │ ├── DistanceSensor.msg │ ├── Ekf2Innovations.msg │ ├── Ekf2Replay.msg │ ├── EscReport.msg │ ├── EscStatus.msg │ ├── EstimatorStatus.msg │ ├── Fence.msg │ ├── FenceVertex.msg │ ├── FilteredBottomFlow.msg │ ├── FollowTarget.msg │ ├── FwPosCtrlStatus.msg │ ├── FwVirtualAttitudeSetpoint.msg │ ├── FwVirtualRatesSetpoint.msg │ ├── GeofenceResult.msg │ ├── GpsDump.msg │ ├── GpsInjectData.msg │ ├── HilSensor.msg │ ├── HomePosition.msg │ ├── InputRc.msg │ ├── LogMessage.msg │ ├── LowStack.msg │ ├── ManualControlSetpoint.msg │ ├── MavlinkLog.msg │ ├── McAttCtrlStatus.msg │ ├── McVirtualAttitudeSetpoint.msg │ ├── McVirtualRatesSetpoint.msg │ ├── Mission.msg │ ├── MissionResult.msg │ ├── MountOrientation.msg │ ├── MultirotorMotorLimits.msg │ ├── OffboardControlMode.msg │ ├── OpticalFlow.msg │ ├── OutputPwm.msg │ ├── ParameterUpdate.msg │ ├── PositionSetpoint.msg │ ├── PositionSetpointTriplet.msg │ ├── PwmInput.msg │ ├── QshellReq.msg │ ├── RcChannels.msg │ ├── RcParameterMap.msg │ ├── Safety.msg │ ├── SatelliteInfo.msg │ ├── SensorAccel.msg │ ├── SensorBaro.msg │ ├── SensorCombined.msg │ ├── SensorCorrection.msg │ ├── SensorGyro.msg │ ├── SensorMag.msg │ ├── SensorPreflight.msg │ ├── ServorailStatus.msg │ ├── SubsystemInfo.msg │ ├── SystemPower.msg │ ├── TecsStatus.msg │ ├── TelemetryStatus.msg │ ├── TestMotor.msg │ ├── TimeOffset.msg │ ├── TransponderReport.msg │ ├── UavcanParameterRequest.msg │ ├── UavcanParameterValue.msg │ ├── UlogStream.msg │ ├── UlogStreamAck.msg │ ├── VehicleAttitude.msg │ ├── VehicleAttitudeSetpoint.msg │ ├── VehicleCommand.msg │ ├── VehicleCommandAck.msg │ ├── VehicleControlMode.msg │ ├── VehicleForceSetpoint.msg │ ├── VehicleGlobalPosition.msg │ ├── VehicleGlobalVelocitySetpoint.msg │ ├── VehicleGpsPosition.msg │ ├── VehicleLandDetected.msg │ ├── VehicleLocalPosition.msg │ ├── VehicleLocalPositionSetpoint.msg │ ├── VehicleRatesSetpoint.msg │ ├── VehicleRoi.msg │ ├── VehicleStatus.msg │ ├── VisionPositionEstimate.msg │ ├── VtolVehicleStatus.msg │ └── WindEstimate.msg └── package.xml ├── px4_msgs_ros2 ├── CMakeLists.txt ├── msg │ ├── ActuatorArmed.msg │ ├── ActuatorControls.msg │ ├── ActuatorDirect.msg │ ├── ActuatorOutputs.msg │ ├── AdcReport.msg │ ├── Airspeed.msg │ ├── AttPosMocap.msg │ ├── BatteryStatus.msg │ ├── CameraTrigger.msg │ ├── CollisionReport.msg │ ├── CommanderState.msg │ ├── ControlState.msg │ ├── Cpuload.msg │ ├── DebugKeyValue.msg │ ├── DifferentialPressure.msg │ ├── DistanceSensor.msg │ ├── Ekf2Innovations.msg │ ├── Ekf2Replay.msg │ ├── EscReport.msg │ ├── EscStatus.msg │ ├── EstimatorStatus.msg │ ├── Fence.msg │ ├── FenceVertex.msg │ ├── FilteredBottomFlow.msg │ ├── FollowTarget.msg │ ├── FwPosCtrlStatus.msg │ ├── FwVirtualAttitudeSetpoint.msg │ ├── FwVirtualRatesSetpoint.msg │ ├── GeofenceResult.msg │ ├── GpsDump.msg │ ├── GpsInjectData.msg │ ├── HilSensor.msg │ ├── HomePosition.msg │ ├── InputRc.msg │ ├── LogMessage.msg │ ├── LowStack.msg │ ├── ManualControlSetpoint.msg │ ├── MavlinkLog.msg │ ├── McAttCtrlStatus.msg │ ├── McVirtualAttitudeSetpoint.msg │ ├── McVirtualRatesSetpoint.msg │ ├── Mission.msg │ ├── MissionResult.msg │ ├── MountOrientation.msg │ ├── MultirotorMotorLimits.msg │ ├── OffboardControlMode.msg │ ├── OpticalFlow.msg │ ├── OutputPwm.msg │ ├── ParameterUpdate.msg │ ├── PositionSetpoint.msg │ ├── PositionSetpointTriplet.msg │ ├── PwmInput.msg │ ├── QshellReq.msg │ ├── RcChannels.msg │ ├── RcParameterMap.msg │ ├── Safety.msg │ ├── SatelliteInfo.msg │ ├── SensorAccel.msg │ ├── SensorBaro.msg │ ├── SensorCombined.msg │ ├── SensorCorrection.msg │ ├── SensorGyro.msg │ ├── SensorMag.msg │ ├── SensorPreflight.msg │ ├── ServorailStatus.msg │ ├── SubsystemInfo.msg │ ├── SystemPower.msg │ ├── TecsStatus.msg │ ├── TelemetryStatus.msg │ ├── TestMotor.msg │ ├── TimeOffset.msg │ ├── TransponderReport.msg │ ├── UavcanParameterRequest.msg │ ├── UavcanParameterValue.msg │ ├── UlogStream.msg │ ├── UlogStreamAck.msg │ ├── VehicleAttitude.msg │ ├── VehicleAttitudeSetpoint.msg │ ├── VehicleCommand.msg │ ├── VehicleCommandAck.msg │ ├── VehicleControlMode.msg │ ├── VehicleForceSetpoint.msg │ ├── VehicleGlobalPosition.msg │ ├── VehicleGlobalVelocitySetpoint.msg │ ├── VehicleGpsPosition.msg │ ├── VehicleLandDetected.msg │ ├── VehicleLocalPosition.msg │ ├── VehicleLocalPositionSetpoint.msg │ ├── VehicleRatesSetpoint.msg │ ├── VehicleRoi.msg │ ├── VehicleStatus.msg │ ├── VisionPositionEstimate.msg │ ├── VtolVehicleStatus.msg │ └── WindEstimate.msg ├── package.xml └── scripts │ └── copy_and_rename.py ├── px4_to_ros2_PoC ├── README.rst ├── doc │ └── bridge-ROS2.png ├── latency │ ├── AMENT_IGNORE │ ├── micrortps_agent │ │ ├── CMakeLists.txt │ │ ├── UART_node.cxx │ │ ├── UART_node.h │ │ ├── microRTPS_agent.cxx │ │ ├── sensor_combined_.cxx │ │ ├── sensor_combined_.h │ │ ├── sensor_combined_PubSubTypes.cxx │ │ ├── sensor_combined_PubSubTypes.h │ │ ├── sensor_combined_Publisher.cxx │ │ ├── sensor_combined_Publisher.h │ │ ├── sensor_combined_Subscriber.cxx │ │ └── sensor_combined_Subscriber.h │ └── micrortps_client │ │ ├── CMakeLists.txt │ │ ├── UART_node.cxx │ │ ├── UART_node.h │ │ └── microRTPS_client.cpp ├── micrortps_agent │ ├── AMENT_IGNORE │ ├── CMakeLists.txt │ ├── UART_node.cxx │ ├── UART_node.h │ ├── microRTPS_agent.cxx │ ├── sensor_combined_.cxx │ ├── sensor_combined_.h │ ├── sensor_combined_PubSubTypes.cxx │ ├── sensor_combined_PubSubTypes.h │ ├── sensor_combined_Publisher.cxx │ ├── sensor_combined_Publisher.h │ ├── sensor_combined_Subscriber.cxx │ └── sensor_combined_Subscriber.h ├── micrortps_client │ ├── AMENT_IGNORE │ ├── CMakeLists.txt │ ├── UART_node.cxx │ ├── UART_node.h │ └── microRTPS_client.cpp ├── px4_msgs │ ├── CMakeLists.txt │ ├── msg │ │ ├── ActuatorArmed.msg │ │ ├── ActuatorControls.msg │ │ ├── ActuatorDirect.msg │ │ ├── ActuatorOutputs.msg │ │ ├── AdcReport.msg │ │ ├── Airspeed.msg │ │ ├── AttPosMocap.msg │ │ ├── BatteryStatus.msg │ │ ├── CameraTrigger.msg │ │ ├── CollisionReport.msg │ │ ├── CommanderState.msg │ │ ├── ControlState.msg │ │ ├── Cpuload.msg │ │ ├── DebugKeyValue.msg │ │ ├── DifferentialPressure.msg │ │ ├── DistanceSensor.msg │ │ ├── Ekf2Innovations.msg │ │ ├── Ekf2Replay.msg │ │ ├── EscReport.msg │ │ ├── EscStatus.msg │ │ ├── EstimatorStatus.msg │ │ ├── Fence.msg │ │ ├── FenceVertex.msg │ │ ├── FilteredBottomFlow.msg │ │ ├── FollowTarget.msg │ │ ├── FwPosCtrlStatus.msg │ │ ├── FwVirtualAttitudeSetpoint.msg │ │ ├── FwVirtualRatesSetpoint.msg │ │ ├── GeofenceResult.msg │ │ ├── GpsDump.msg │ │ ├── GpsInjectData.msg │ │ ├── HilSensor.msg │ │ ├── HomePosition.msg │ │ ├── InputRc.msg │ │ ├── LogMessage.msg │ │ ├── LowStack.msg │ │ ├── ManualControlSetpoint.msg │ │ ├── MavlinkLog.msg │ │ ├── McAttCtrlStatus.msg │ │ ├── McVirtualAttitudeSetpoint.msg │ │ ├── McVirtualRatesSetpoint.msg │ │ ├── Mission.msg │ │ ├── MissionResult.msg │ │ ├── MountOrientation.msg │ │ ├── MultirotorMotorLimits.msg │ │ ├── OffboardControlMode.msg │ │ ├── OpticalFlow.msg │ │ ├── OutputPwm.msg │ │ ├── ParameterUpdate.msg │ │ ├── PositionSetpoint.msg │ │ ├── PositionSetpointTriplet.msg │ │ ├── PwmInput.msg │ │ ├── QshellReq.msg │ │ ├── RcChannels.msg │ │ ├── RcParameterMap.msg │ │ ├── Safety.msg │ │ ├── SatelliteInfo.msg │ │ ├── SensorAccel.msg │ │ ├── SensorBaro.msg │ │ ├── SensorCombined.msg │ │ ├── SensorCorrection.msg │ │ ├── SensorGyro.msg │ │ ├── SensorMag.msg │ │ ├── SensorPreflight.msg │ │ ├── ServorailStatus.msg │ │ ├── SubsystemInfo.msg │ │ ├── SystemPower.msg │ │ ├── TecsStatus.msg │ │ ├── TelemetryStatus.msg │ │ ├── TestMotor.msg │ │ ├── TimeOffset.msg │ │ ├── TransponderReport.msg │ │ ├── UavcanParameterRequest.msg │ │ ├── UavcanParameterValue.msg │ │ ├── UlogStream.msg │ │ ├── UlogStreamAck.msg │ │ ├── VehicleAttitude.msg │ │ ├── VehicleAttitudeSetpoint.msg │ │ ├── VehicleCommand.msg │ │ ├── VehicleCommandAck.msg │ │ ├── VehicleControlMode.msg │ │ ├── VehicleForceSetpoint.msg │ │ ├── VehicleGlobalPosition.msg │ │ ├── VehicleGlobalVelocitySetpoint.msg │ │ ├── VehicleGpsPosition.msg │ │ ├── VehicleLandDetected.msg │ │ ├── VehicleLocalPosition.msg │ │ ├── VehicleLocalPositionSetpoint.msg │ │ ├── VehicleRatesSetpoint.msg │ │ ├── VehicleRoi.msg │ │ ├── VehicleStatus.msg │ │ ├── VisionPositionEstimate.msg │ │ ├── VtolVehicleStatus.msg │ │ └── WindEstimate.msg │ ├── package.xml │ └── scripts │ │ └── copy_and_rename.py └── sensor_combined_listener │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ ├── sensor_combined_latency.cpp │ └── sensor_combined_listener.cpp ├── ros1_bridge ├── include │ └── ros1_bridge │ │ └── factory.hpp └── src │ └── static_bridge.cpp └── sensor_combined_ros1 ├── CMakeLists.txt ├── package.xml └── src └── listener.cpp /doc/PX4-to-ros.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/eProsima/px4_to_ros/7329dda1d1614c27da982f32a4d8fc7afd03b957/doc/PX4-to-ros.png -------------------------------------------------------------------------------- /doc/complete_loop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/eProsima/px4_to_ros/7329dda1d1614c27da982f32a4d8fc7afd03b957/doc/complete_loop.png -------------------------------------------------------------------------------- /micrortps_agent/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.12) 2 | project(micrortps_receiver) 3 | 4 | # Find requirements 5 | find_package(fastrtps REQUIRED) 6 | find_package(fastcdr REQUIRED) 7 | 8 | # Set C++11 9 | include(CheckCXXCompilerFlag) 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG OR 11 | CMAKE_CXX_COMPILER_ID MATCHES "Clang") 12 | check_cxx_compiler_flag(--std=c++11 SUPPORTS_CXX11) 13 | if(SUPPORTS_CXX11) 14 | add_compile_options(--std=c++11) 15 | else() 16 | message(FATAL_ERROR "Compiler doesn't support C++11") 17 | endif() 18 | endif() 19 | 20 | file(GLOB MICRORTPS_AGENT_SOURCES *.cxx) 21 | add_executable(micrortps_agent ${MICRORTPS_AGENT_SOURCES}) 22 | target_link_libraries(micrortps_agent fastrtps fastcdr) -------------------------------------------------------------------------------- /micrortps_agent/UART_node.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | 20 | 21 | class UART_node 22 | { 23 | public: 24 | UART_node(); 25 | virtual ~UART_node(); 26 | 27 | uint8_t init_uart(const char * uart_name); 28 | uint8_t close_uart(); 29 | int16_t readFromUART(char* topic_ID, char out_buffer[], char rx_buffer[], uint32_t &rx_buff_pos, uint32_t max_size); 30 | int16_t writeToUART(const char topic_ID, char buffer[], uint32_t length); 31 | 32 | protected: 33 | uint16_t crc16_byte(uint16_t crc, const uint8_t data); 34 | uint16_t crc16(uint8_t const *buffer, size_t len); 35 | 36 | protected: 37 | 38 | int m_uart_filestream; 39 | }; 40 | -------------------------------------------------------------------------------- /micrortps_agent/sensor_combined_PubSubTypes.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | /*! 16 | * @file sensor_combined_PubSubTypes.h 17 | * This header file contains the declaration of the serialization functions. 18 | * 19 | * This file was generated by the tool fastcdrgen. 20 | */ 21 | 22 | 23 | #ifndef _SENSOR_COMBINED__PUBSUBTYPES_H_ 24 | #define _SENSOR_COMBINED__PUBSUBTYPES_H_ 25 | 26 | #include 27 | 28 | using namespace eprosima::fastrtps; 29 | 30 | #include "sensor_combined_.h" 31 | 32 | /*! 33 | * @brief This class represents the TopicDataType of the type sensor_combined_ defined by the user in the IDL file. 34 | * @ingroup SENSOR_COMBINED_ 35 | */ 36 | class sensor_combined_PubSubType : public TopicDataType { 37 | public: 38 | typedef sensor_combined_ type; 39 | 40 | sensor_combined_PubSubType(); 41 | virtual ~sensor_combined_PubSubType(); 42 | bool serialize(void *data, SerializedPayload_t *payload); 43 | bool deserialize(SerializedPayload_t *payload, void *data); 44 | std::function getSerializedSizeProvider(void* data); 45 | bool getKey(void *data, InstanceHandle_t *ihandle); 46 | void* createData(); 47 | void deleteData(void * data); 48 | MD5 m_md5; 49 | unsigned char* m_keyBuffer; 50 | }; 51 | 52 | #endif // _sensor_combined__PUBSUBTYPE_H_ -------------------------------------------------------------------------------- /micrortps_agent/sensor_combined_Publisher.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | /*! 16 | * @file sensor_combined_Publisher.h 17 | * This header file contains the declaration of the publisher functions. 18 | * 19 | * This file was generated by the tool fastcdrgen. 20 | */ 21 | 22 | 23 | #ifndef _sensor_combined__PUBLISHER_H_ 24 | #define _sensor_combined__PUBLISHER_H_ 25 | 26 | #include 27 | #include 28 | 29 | #include "sensor_combined_PubSubTypes.h" 30 | 31 | using namespace eprosima::fastrtps; 32 | 33 | class sensor_combined_Publisher 34 | { 35 | public: 36 | sensor_combined_Publisher(); 37 | virtual ~sensor_combined_Publisher(); 38 | bool init(); 39 | void run(); 40 | void publish(sensor_combined_* st); 41 | private: 42 | Participant *mp_participant; 43 | Publisher *mp_publisher; 44 | 45 | class PubListener : public PublisherListener 46 | { 47 | public: 48 | PubListener() : n_matched(0){}; 49 | ~PubListener(){}; 50 | void onPublicationMatched(Publisher* pub,MatchingInfo& info); 51 | int n_matched; 52 | } m_listener; 53 | sensor_combined_PubSubType myType; 54 | }; 55 | 56 | #endif // _sensor_combined__PUBLISHER_H_ -------------------------------------------------------------------------------- /micrortps_client/UART_node.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | 20 | 21 | class UART_node 22 | { 23 | public: 24 | UART_node(); 25 | virtual ~UART_node(); 26 | 27 | uint8_t init_uart(const char * uart_name); 28 | uint8_t close_uart(); 29 | int16_t readFromUART(char* topic_ID, char out_buffer[], char rx_buffer[], uint32_t &rx_buff_pos, uint32_t max_size); 30 | int16_t writeToUART(const char topic_ID, char buffer[], uint32_t length); 31 | 32 | protected: 33 | uint16_t crc16_byte(uint16_t crc, const uint8_t data); 34 | uint16_t crc16(uint8_t const *buffer, size_t len); 35 | 36 | protected: 37 | 38 | int m_uart_filestream; 39 | }; 40 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ActuatorArmed.msg: -------------------------------------------------------------------------------- 1 | 2 | bool armed # Set to true if system is armed 3 | bool prearmed # Set to true if the actuator safety is disabled but motors are not armed 4 | bool ready_to_arm # Set to true if system is ready to be armed 5 | bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL) 6 | bool manual_lockdown # Set to true if manual throttle kill switch is engaged 7 | bool force_failsafe # Set to true if the actuators are forced to the failsafe position 8 | bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics 9 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ActuatorControls.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATOR_CONTROLS = 8 2 | uint8 NUM_ACTUATOR_CONTROL_GROUPS = 4 3 | uint8 INDEX_ROLL = 0 4 | uint8 INDEX_PITCH = 1 5 | uint8 INDEX_YAW = 2 6 | uint8 INDEX_THROTTLE = 3 7 | uint8 INDEX_FLAPS = 4 8 | uint8 INDEX_SPOILERS = 5 9 | uint8 INDEX_AIRBRAKES = 6 10 | uint8 INDEX_LANDING_GEAR = 7 11 | uint8 GROUP_INDEX_ATTITUDE = 0 12 | uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1 13 | uint64 timestamp_sample # the timestamp the data this control response is based on was sampled 14 | float32[8] control 15 | 16 | # TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3 17 | # TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc 18 | 19 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ActuatorDirect.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATORS_DIRECT = 16 2 | uint32 nvalues # number of valid values 3 | float32[16] values # actuator values, from -1 to 1 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ActuatorOutputs.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATOR_OUTPUTS = 16 2 | uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking 3 | uint32 noutputs # valid outputs 4 | float32[16] output # output data, in natural output units 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/AdcReport.msg: -------------------------------------------------------------------------------- 1 | int16[8] channel_id # ADC channel IDs, negative for non-existent 2 | float32[8] channel_value # ADC channel value in volt, valid if channel ID is positive 3 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/Airspeed.msg: -------------------------------------------------------------------------------- 1 | float32 indicated_airspeed_m_s # indicated airspeed in meters per second, -1 if unknown 2 | float32 true_airspeed_m_s # true filtered airspeed in meters per second, -1 if unknown 3 | float32 true_airspeed_unfiltered_m_s # true airspeed in meters per second, -1 if unknown 4 | float32 air_temperature_celsius # air temperature in degrees celsius, -1000 if unknown 5 | float32 confidence # confidence value from 0 to 1 for this sensor 6 | float32 differential_pressure_filtered_pa # filtered differential pressure, can be negative 7 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/AttPosMocap.msg: -------------------------------------------------------------------------------- 1 | uint32 id # ID of the estimator, commonly the component ID of the incoming message 2 | 3 | uint64 timestamp_received # timestamp when the estimate was received 4 | 5 | float32[4] q # Estimated attitude as quaternion 6 | 7 | float32 x # X position in meters in NED earth-fixed frame 8 | float32 y # Y position in meters in NED earth-fixed frame 9 | float32 z # Z position in meters in NED earth-fixed frame (negative altitude) 10 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/BatteryStatus.msg: -------------------------------------------------------------------------------- 1 | float32 voltage_v # Battery voltage in volts, 0 if unknown 2 | float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown 3 | float32 current_a # Battery current in amperes, -1 if unknown 4 | float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown 5 | float32 discharged_mah # Discharged amount in mAh, -1 if unknown 6 | float32 remaining # From 1 to 0, -1 if unknown 7 | float32 scale # Power scaling factor, >= 1, or -1 if unknown 8 | int32 cell_count # Number of cells 9 | bool connected # Wether or not a battery is connected 10 | #bool is_powering_off # Power off event imminent indication, false if unknown 11 | 12 | 13 | uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active 14 | uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage 15 | uint8 BATTERY_WARNING_CRITICAL = 2 # alerting of critical voltage 16 | 17 | uint8 warning # current battery warning 18 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/CameraTrigger.msg: -------------------------------------------------------------------------------- 1 | 2 | uint32 seq # Image sequence 3 | 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/CollisionReport.msg: -------------------------------------------------------------------------------- 1 | uint8 src 2 | uint32 id 3 | uint8 action 4 | uint8 threat_level 5 | float32 time_to_minimum_delta 6 | float32 altitude_minimum_delta 7 | float32 horizontal_minimum_delta 8 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/CommanderState.msg: -------------------------------------------------------------------------------- 1 | # Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link. 2 | uint8 MAIN_STATE_MANUAL = 0 3 | uint8 MAIN_STATE_ALTCTL = 1 4 | uint8 MAIN_STATE_POSCTL = 2 5 | uint8 MAIN_STATE_AUTO_MISSION = 3 6 | uint8 MAIN_STATE_AUTO_LOITER = 4 7 | uint8 MAIN_STATE_AUTO_RTL = 5 8 | uint8 MAIN_STATE_ACRO = 6 9 | uint8 MAIN_STATE_OFFBOARD = 7 10 | uint8 MAIN_STATE_STAB = 8 11 | uint8 MAIN_STATE_RATTITUDE = 9 12 | uint8 MAIN_STATE_AUTO_TAKEOFF = 10 13 | uint8 MAIN_STATE_AUTO_LAND = 11 14 | uint8 MAIN_STATE_AUTO_FOLLOW_TARGET = 12 15 | uint8 MAIN_STATE_MAX = 13 16 | 17 | 18 | uint8 main_state # main state machine 19 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ControlState.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message CONTROL_SYSTEM_STATE, but for onboard use */ 2 | uint8 AIRSPD_MODE_MEAS = 0 # airspeed is measured airspeed from sensor 3 | uint8 AIRSPD_MODE_EST = 1 # airspeed is estimated by body velocity 4 | uint8 AIRSPD_MODE_DISABLED = 2 # airspeed is disabled 5 | 6 | float32 x_acc # X acceleration in body frame 7 | float32 y_acc # Y acceleration in body frame 8 | float32 z_acc # Z acceleration in body frame 9 | float32 x_vel # X velocity in body frame 10 | float32 y_vel # Y velocity in body frame 11 | float32 z_vel # Z velocity in body frame 12 | float32 x_pos # X position in local earth frame 13 | float32 y_pos # Y position in local earth frame 14 | float32 z_pos # z position in local earth frame 15 | float32 airspeed # Airspeed, estimated 16 | bool airspeed_valid # False: Non-finite values or non-updating sensor 17 | float32[3] vel_variance # Variance in body velocity estimate 18 | float32[3] pos_variance # Variance in local position estimate 19 | float32[4] q # Attitude Quaternion 20 | float32[4] delta_q_reset # Amount by which quaternion has changed during last reset 21 | uint8 quat_reset_counter # Quaternion reset counter 22 | float32 roll_rate # Roll body angular rate (rad/s, x forward/y right/z down) - corrected for bias 23 | float32 pitch_rate # Pitch body angular rate (rad/s, x forward/y right/z down) - corrected for bias 24 | float32 yaw_rate # Yaw body angular rate (rad/s, x forward/y right/z down) - corrected for bias 25 | float32 horz_acc_mag # low pass filtered magnitude of the horizontal acceleration 26 | float32 roll_rate_bias # Roll body angular rate bias (rad/s, x forward) - subtract from uncorrected gyro data 27 | float32 pitch_rate_bias # Pitch body angular rate bias (rad/s, y right) - subtract from uncorrected gyro data 28 | float32 yaw_rate_bias # Yaw body angular rate bias (rad/s, z down) - subtract from uncorrected gyro data 29 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/Cpuload.msg: -------------------------------------------------------------------------------- 1 | float32 load # processor load from 0 to 1 2 | float32 ram_usage # RAM usage from 0 to 1 3 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/DebugKeyValue.msg: -------------------------------------------------------------------------------- 1 | uint32 timestamp_ms # in milliseconds since system start 2 | int8[10] key # max. 10 characters as key / name 3 | float32 value # the value to send as debug output 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/DifferentialPressure.msg: -------------------------------------------------------------------------------- 1 | uint64 error_count # Number of errors detected by driver 2 | float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative) 3 | float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading 4 | float32 max_differential_pressure_pa # Maximum differential pressure reading 5 | float32 temperature # Temperature provided by sensor, -1000.0f if unknown 6 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/DistanceSensor.msg: -------------------------------------------------------------------------------- 1 | # DISTANCE_SENSOR message data 2 | 3 | 4 | float32 min_distance # Minimum distance the sensor can measure (in m) 5 | float32 max_distance # Maximum distance the sensor can measure (in m) 6 | float32 current_distance # Current distance reading (in m) 7 | float32 covariance # Measurement covariance (in m), 0 for unknown / invalid readings 8 | 9 | uint8 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 | uint8 id # Onboard ID of the sensor 16 | 17 | uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum 18 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/Ekf2Innovations.msg: -------------------------------------------------------------------------------- 1 | float32[6] vel_pos_innov # velocity and position innovations 2 | float32[3] mag_innov # earth magnetic field innovations 3 | float32 heading_innov # heading innovation 4 | float32 airspeed_innov # airspeed innovation 5 | float32 beta_innov # synthetic sideslip innovation 6 | float32[2] flow_innov # flow innovation 7 | float32 hagl_innov # innovation from the terrain estimator for the height above ground level measurement (m) 8 | float32[6] vel_pos_innov_var # velocity and position innovation variances 9 | float32[3] mag_innov_var # earth magnetic field innovation variance 10 | float32 heading_innov_var # heading innovation variance 11 | float32 airspeed_innov_var # Airspeed innovation variance 12 | float32 beta_innov_var # synthetic sideslip innovation variance 13 | float32[2] flow_innov_var # flow innovation variance 14 | float32 hagl_innov_var # innovation variance from the terrain estimator for the height above ground level measurement (m^2) 15 | float32[3] output_tracking_error # return a vector containing the output predictor angular, velocity and position tracking error magnitudes (rad), (m/s), (m) 16 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/EscReport.msg: -------------------------------------------------------------------------------- 1 | uint8 esc_vendor # Vendor of current ESC 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 | float32 esc_setpoint # setpoint of current ESC 8 | uint16 esc_setpoint_raw # setpoint of current ESC (Value sent to ESC) 9 | uint16 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver) 10 | uint16 esc_version # Version of current ESC - if supported 11 | uint16 esc_state # State of ESC - depend on Vendor 12 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/EscStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs 2 | 3 | uint8 ESC_VENDOR_GENERIC = 0 # generic ESC 4 | uint8 ESC_VENDOR_MIKROKOPTER = 1 # Mikrokopter 5 | uint8 ESC_VENDOR_GRAUPNER_HOTT = 2 # Graupner HoTT ESC 6 | uint8 ESC_VENDOR_TAP = 3 # TAP ESC 7 | 8 | uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC 9 | uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC 10 | uint8 ESC_CONNECTION_TYPE_ONESHOOT = 2 # One Shoot PPM 11 | uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C 12 | uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus 13 | 14 | uint16 counter # incremented by the writing thread everytime new data is stored 15 | 16 | uint8 esc_count # number of connected ESCs 17 | uint8 esc_connectiontype # how ESCs connected to the system 18 | 19 | esc_report[8] esc 20 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/Fence.msg: -------------------------------------------------------------------------------- 1 | uint8 GEOFENCE_MAX_VERTICES = 16 2 | 3 | uint32 count # number of actual vertices 4 | fence_vertex[16] vertices # geofence positions 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/FenceVertex.msg: -------------------------------------------------------------------------------- 1 | float32 lat # latitude in degrees, worst case float precision gives us 2 meter resolution at the equator 2 | float32 lon # longitude in degrees, worst case float precision gives us 2 meter resolution at the equator 3 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/FilteredBottomFlow.msg: -------------------------------------------------------------------------------- 1 | # Filtered bottom flow in bodyframe. 2 | 3 | float32 sumx # Integrated bodyframe x flow in meters 4 | float32 sumy # Integrated bodyframe y flow in meters 5 | 6 | float32 vx # Flow bodyframe x speed, m/s 7 | float32 vy # Flow bodyframe y Speed, m/s 8 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/FollowTarget.msg: -------------------------------------------------------------------------------- 1 | float64 lat # target position (deg * 1e7) 2 | float64 lon # target position (deg * 1e7) 3 | float32 alt # target position 4 | float32 vy # target vel in y 5 | float32 vx # target vel in x 6 | float32 vz # target vel in z 7 | uint8 est_cap # target reporting capabilities 8 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/FwPosCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | float32 nav_roll 2 | float32 nav_pitch 3 | float32 nav_bearing 4 | 5 | float32 target_bearing 6 | float32 wp_dist 7 | float32 xtrack_error 8 | float32 turn_distance # the optimal distance to a waypoint to switch to the next 9 | 10 | float32 landing_horizontal_slope_displacement 11 | float32 landing_slope_angle_rad 12 | float32 landing_flare_length 13 | bool abort_landing 14 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/FwVirtualAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame 19 | bool R_valid # Set to true if rotation matrix is valid 20 | 21 | # For quaternion-based attitude control 22 | float32[4] q_d # Desired quaternion for quaternion control 23 | bool q_d_valid # Set to true if quaternion vector is valid 24 | float32[4] q_e # Attitude error in quaternion 25 | bool q_e_valid # Set to true if quaternion error vector is valid 26 | 27 | float32 thrust # Thrust in Newton the power system should generate 28 | 29 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 30 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 31 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 32 | 33 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 34 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 35 | 36 | bool apply_flaps 37 | 38 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 39 | # TOPICS fw_virtual_attitude_setpoint 40 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/FwVirtualRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/GeofenceResult.msg: -------------------------------------------------------------------------------- 1 | uint8 GF_ACTION_NONE = 0 # no action on geofence violation 2 | uint8 GF_ACTION_WARN = 1 # critical mavlink message 3 | uint8 GF_ACTION_LOITER = 2 # switch to AUTO|LOITER 4 | uint8 GF_ACTION_RTL = 3 # switch to AUTO|RTL 5 | uint8 GF_ACTION_TERMINATE = 4 # flight termination 6 | 7 | bool geofence_violated # true if the geofence is violated 8 | uint8 geofence_action # action to take when geofence is violated -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/GpsDump.msg: -------------------------------------------------------------------------------- 1 | # This message is used to dump the raw gps communication to the log. 2 | # Set the parameter GPS_DUMP_COMM to 1 to use this. 3 | 4 | uint8 len # length of data, MSB bit set = message to the gps device, 5 | # clear = message from the device 6 | uint8[79] data # data to write to the log 7 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/GpsInjectData.msg: -------------------------------------------------------------------------------- 1 | uint8 len # length of data 2 | uint8 flags # LSB: 1=fragmented 3 | uint8[182] data # data to write to GPS device (RTCM message) 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/HomePosition.msg: -------------------------------------------------------------------------------- 1 | # GPS home position in WGS84 coordinates. 2 | 3 | float64 lat # Latitude in degrees 4 | float64 lon # Longitude in degrees 5 | float32 alt # Altitude in meters (AMSL) 6 | 7 | float32 x # X coordinate in meters 8 | float32 y # Y coordinate in meters 9 | float32 z # Z coordinate in meters 10 | 11 | float32 yaw # Yaw angle in radians 12 | float32 direction_x # Takeoff direction in NED X 13 | float32 direction_y # Takeoff direction in NED Y 14 | float32 direction_z # Takeoff direction in NED Z 15 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/InputRc.msg: -------------------------------------------------------------------------------- 1 | uint8 RC_INPUT_SOURCE_UNKNOWN = 0 2 | uint8 RC_INPUT_SOURCE_PX4FMU_PPM = 1 3 | uint8 RC_INPUT_SOURCE_PX4IO_PPM = 2 4 | uint8 RC_INPUT_SOURCE_PX4IO_SPEKTRUM = 3 5 | uint8 RC_INPUT_SOURCE_PX4IO_SBUS = 4 6 | uint8 RC_INPUT_SOURCE_PX4IO_ST24 = 5 7 | uint8 RC_INPUT_SOURCE_MAVLINK = 6 8 | uint8 RC_INPUT_SOURCE_QURT = 7 9 | uint8 RC_INPUT_SOURCE_PX4FMU_SPEKTRUM = 8 10 | uint8 RC_INPUT_SOURCE_PX4FMU_SBUS = 9 11 | uint8 RC_INPUT_SOURCE_PX4FMU_ST24 = 10 12 | uint8 RC_INPUT_SOURCE_PX4FMU_SUMD = 11 13 | uint8 RC_INPUT_SOURCE_PX4FMU_DSM = 12 14 | uint8 RC_INPUT_SOURCE_PX4IO_SUMD = 13 15 | 16 | uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. 17 | 18 | uint64 timestamp_last_signal # last valid reception time 19 | uint32 channel_count # number of channels actually being seen 20 | int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception 21 | 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. 22 | 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. 23 | 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 funtionality. 24 | 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 funtionality. 25 | uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems 26 | uint8 input_source # Input source 27 | uint16[18] values # measured pulse widths for each of the supported channels 28 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/LogMessage.msg: -------------------------------------------------------------------------------- 1 | # A logging message, output with PX4_{WARN,ERR,INFO} 2 | 3 | uint8 severity # log level (same as in the linux kernel, starting with 0) 4 | uint8[127] text 5 | 6 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/LowStack.msg: -------------------------------------------------------------------------------- 1 | uint8 MAX_REPORT_TASK_NAME_LEN = 16 2 | 3 | uint16 stack_free 4 | uint8[16] task_name 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/MavlinkLog.msg: -------------------------------------------------------------------------------- 1 | 2 | uint8[50] text 3 | uint8 severity # log level (same as in the linux kernel, starting with 0) 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/McAttCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | 2 | float32 roll_rate_integ # roll rate inegrator 3 | float32 pitch_rate_integ # pitch rate integrator 4 | float32 yaw_rate_integ # yaw rate integrator 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/McVirtualAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame 19 | bool R_valid # Set to true if rotation matrix is valid 20 | 21 | # For quaternion-based attitude control 22 | float32[4] q_d # Desired quaternion for quaternion control 23 | bool q_d_valid # Set to true if quaternion vector is valid 24 | float32[4] q_e # Attitude error in quaternion 25 | bool q_e_valid # Set to true if quaternion error vector is valid 26 | 27 | float32 thrust # Thrust in Newton the power system should generate 28 | 29 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 30 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 31 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 32 | 33 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 34 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 35 | 36 | bool apply_flaps 37 | 38 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 39 | # TOPICS mc_virtual_attitude_setpoint 40 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/McVirtualRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/Mission.msg: -------------------------------------------------------------------------------- 1 | int32 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1 2 | uint32 count # count of the missions stored in the dataman 3 | int32 current_seq # default -1, start at the one changed latest 4 | 5 | # TOPICS mission offboard_mission onboard_mission 6 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/MissionResult.msg: -------------------------------------------------------------------------------- 1 | uint32 instance_count # Instance count of this mission. Increments monotonically whenever the mission is modified 2 | uint32 seq_reached # Sequence of the mission item which has been reached 3 | uint32 seq_current # Sequence of the current mission item 4 | uint32 seq_total # Total number of mission items 5 | bool valid # true if mission is valid 6 | bool warning # true if mission is valid, but has potentially problematic items leading to safety warnings 7 | bool reached # true if mission has been reached 8 | bool finished # true if mission has been completed 9 | bool stay_in_failsafe # true if the commander should not switch out of the failsafe mode 10 | bool flight_termination # true if the navigator demands a flight termination from the commander app 11 | bool item_do_jump_changed # true if the number of do jumps remaining has changed 12 | uint32 item_changed_index # indicate which item has changed 13 | uint32 item_do_jump_remaining # set to the number of do jumps remaining for that item 14 | bool mission_failure # true if the mission cannot continue or be completed for some reason 15 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/MountOrientation.msg: -------------------------------------------------------------------------------- 1 | float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad 2 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/MultirotorMotorLimits.msg: -------------------------------------------------------------------------------- 1 | uint16 saturation_status # Integer bit mask indicating which axes in the control mixer are saturated 2 | # 0 - True if any motor is saturated at the upper limit 3 | # 1 - True if any motor is saturated at the lower limit 4 | # 2 - True if a positive roll increment will increase motor saturation 5 | # 3 - True if negative roll increment will increase motor saturation 6 | # 4 - True if positive pitch increment will increase motor saturation 7 | # 5 - True if negative pitch increment will increase motor saturation 8 | # 6 - True if positive yaw increment will increase motor saturation 9 | # 7 - True if negative yaw increment will increase motor saturation 10 | # 8 - True if positive thrust increment will increase motor saturation 11 | # 9 - True if negative thrust increment will increase motor saturation 12 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/OffboardControlMode.msg: -------------------------------------------------------------------------------- 1 | # Off-board control mode 2 | 3 | bool ignore_thrust 4 | bool ignore_attitude 5 | bool ignore_bodyrate 6 | bool ignore_position 7 | bool ignore_velocity 8 | bool ignore_acceleration_force 9 | bool ignore_alt_hold 10 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/OpticalFlow.msg: -------------------------------------------------------------------------------- 1 | # Optical flow in XYZ body frame in SI units. 2 | # @see http://en.wikipedia.org/wiki/International_System_of_Units 3 | 4 | uint8 sensor_id # id of the sensor emitting the flow value 5 | float32 pixel_flow_x_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the X body axis 6 | float32 pixel_flow_y_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the Y body axis 7 | float32 gyro_x_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the X body axis 8 | float32 gyro_y_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the Y body axis 9 | float32 gyro_z_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the Z body axis 10 | float32 ground_distance_m # Altitude / distance to ground in meters 11 | uint32 integration_timespan # accumulation timespan in microseconds 12 | uint32 time_since_last_sonar_update # time since last sonar update in microseconds 13 | uint16 frame_count_since_last_readout # number of accumulated frames in timespan 14 | int16 gyro_temperature # Temperature * 100 in centi-degrees Celsius 15 | uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: maximum quality 16 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/OutputPwm.msg: -------------------------------------------------------------------------------- 1 | uint8 PWM_OUTPUT_MAX_CHANNELS = 16 2 | uint16[16] values 3 | uint32 channel_count 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ParameterUpdate.msg: -------------------------------------------------------------------------------- 1 | bool saved # wether the change has already been saved to disk 2 | -------------------------------------------------------------------------------- /px4_msgs_ros1/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 | px4/position_setpoint previous 5 | px4/position_setpoint current 6 | px4/position_setpoint next 7 | 8 | uint8 nav_state # report the navigation state 9 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/PwmInput.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 error_count 3 | uint32 pulse_width # Pulse width, timer counts 4 | uint32 period # Period, timer counts 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/QshellReq.msg: -------------------------------------------------------------------------------- 1 | int32[100] string 2 | uint64 MAX_STRLEN = 100 3 | uint64 strlen 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/RcChannels.msg: -------------------------------------------------------------------------------- 1 | int32 RC_CHANNELS_FUNCTION_MAX=21 2 | uint8 RC_CHANNELS_FUNCTION_THROTTLE=0 3 | uint8 RC_CHANNELS_FUNCTION_ROLL=1 4 | uint8 RC_CHANNELS_FUNCTION_PITCH=2 5 | uint8 RC_CHANNELS_FUNCTION_YAW=3 6 | uint8 RC_CHANNELS_FUNCTION_MODE=4 7 | uint8 RC_CHANNELS_FUNCTION_RETURN=5 8 | uint8 RC_CHANNELS_FUNCTION_POSCTL=6 9 | uint8 RC_CHANNELS_FUNCTION_LOITER=7 10 | uint8 RC_CHANNELS_FUNCTION_OFFBOARD=8 11 | uint8 RC_CHANNELS_FUNCTION_ACRO=9 12 | uint8 RC_CHANNELS_FUNCTION_FLAPS=10 13 | uint8 RC_CHANNELS_FUNCTION_AUX_1=11 14 | uint8 RC_CHANNELS_FUNCTION_AUX_2=12 15 | uint8 RC_CHANNELS_FUNCTION_AUX_3=13 16 | uint8 RC_CHANNELS_FUNCTION_AUX_4=14 17 | uint8 RC_CHANNELS_FUNCTION_AUX_5=15 18 | uint8 RC_CHANNELS_FUNCTION_PARAM_1=16 19 | uint8 RC_CHANNELS_FUNCTION_PARAM_2=17 20 | uint8 RC_CHANNELS_FUNCTION_PARAM_3_5=18 21 | uint8 RC_CHANNELS_FUNCTION_RATTITUDE=19 22 | uint8 RC_CHANNELS_FUNCTION_KILLSWITCH=20 23 | uint8 RC_CHANNELS_FUNCTION_TRANSITION=21 24 | uint8 RC_CHANNELS_FUNCTION_GEAR=22 25 | uint8 RC_CHANNELS_FUNCTION_ARMSWITCH=23 26 | 27 | uint64 timestamp_last_valid # Timestamp of last valid RC signal 28 | float32[18] channels # Scaled to -1..1 (throttle: 0..1) 29 | uint8 channel_count # Number of valid channels 30 | int8[24] function # Functions mapping 31 | uint8 rssi # Receive signal strength indicator (0-100) 32 | bool signal_lost # Control signal lost, should be checked together with topic timeout 33 | uint32 frame_drop_count # Number of dropped frames 34 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/RcParameterMap.msg: -------------------------------------------------------------------------------- 1 | uint8 RC_PARAM_MAP_NCHAN = 3 # This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h 2 | uint8 PARAM_ID_LEN = 16 # corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 3 | 4 | bool[3] valid #true for RC-Param channels which are mapped to a param 5 | int32[3] param_index # corresponding param index, this field is ignored if set to -1, in this case param_id will be used 6 | char[51] param_id # MAP_NCHAN * (ID_LEN + 1) chars, corresponding param id, null terminated 7 | float32[3] scale # scale to map the RC input [-1, 1] to a parameter value 8 | float32[3] value0 # initial value around which the parameter value is changed 9 | float32[3] value_min # minimal parameter value 10 | float32[3] value_max # minimal parameter value 11 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/Safety.msg: -------------------------------------------------------------------------------- 1 | bool safety_switch_available # Set to true if a safety switch is connected 2 | bool safety_off # Set to true if safety is off 3 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SatelliteInfo.msg: -------------------------------------------------------------------------------- 1 | uint8 SAT_INFO_MAX_SATELLITES = 20 2 | 3 | uint8 count # Number of satellites in satellite info 4 | uint8[20] svid # Space vehicle ID [1..255], see scheme below 5 | uint8[20] used # 0: Satellite not used, 1: used for navigation 6 | uint8[20] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite 7 | uint8[20] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg. 8 | uint8[20] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. 9 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorAccel.msg: -------------------------------------------------------------------------------- 1 | uint64 integral_dt # integration time 2 | uint64 error_count 3 | float32 x # acceleration in the NED X board axis in m/s^2 4 | float32 y # acceleration in the NED Y board axis in m/s^2 5 | float32 z # acceleration in the NED Z board axis in m/s^2 6 | float32 x_integral # velocity in the NED X board axis in m/s over the integration time frame 7 | float32 y_integral # velocity in the NED Y board axis in m/s over the integration time frame 8 | float32 z_integral # velocity in the NED Z board axis in m/s over the integration time frame 9 | float32 temperature # temperature in degrees celsius 10 | float32 range_m_s2 # range in m/s^2 (+- this value) 11 | float32 scaling 12 | 13 | int16 x_raw 14 | int16 y_raw 15 | int16 z_raw 16 | int16 temperature_raw 17 | 18 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 19 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorBaro.msg: -------------------------------------------------------------------------------- 1 | float32 pressure # static pressure measurement in millibar 2 | float32 altitude # ISA pressure altitude in meters 3 | float32 temperature # static temperature measurement in deg C 4 | uint64 error_count 5 | uint32 device_id # Sensor ID that must be unique for each baro sensor and must not change 6 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorCombined.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor readings in SI-unit form. 3 | # 4 | # These fields are scaled and offset-compensated where possible and do not 5 | # change with board revisions and sensor updates. 6 | # 7 | 8 | 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 9 | 10 | 11 | # gyro timstamp is equal to the timestamp of the message 12 | float32[3] gyro_rad # average angular rate measured in the XYZ body frame in rad/s over the last gyro sampling period 13 | float32 gyro_integral_dt # gyro measurement sampling period in s 14 | 15 | int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp 16 | float32[3] accelerometer_m_s2 # average value acceleration measured in the XYZ body frame in m/s/s over the last accelerometer sampling period 17 | float32 accelerometer_integral_dt # accelerometer measurement sampling period in s 18 | 19 | int32 magnetometer_timestamp_relative # timestamp + magnetometer_timestamp_relative = Magnetometer timestamp 20 | float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss 21 | 22 | int32 baro_timestamp_relative # timestamp + baro_timestamp_relative = Barometer timestamp 23 | float32 baro_alt_meter # Altitude, already temp. comp. 24 | float32 baro_temp_celcius # Temperature in degrees celsius 25 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorCorrection.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor corrections in SI-unit form for the voted sensor 3 | # 4 | 5 | # Corrections for gyro angular rate outputs where corrected_rate = raw_rate * gyro_scale + gyro_offset 6 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 7 | float32[3] gyro_offset # gyro XYZ offsets in the sensor frame in rad/s 8 | float32[3] gyro_scale # gyro XYZ scale factors in the sensor frame 9 | 10 | # Corrections for acceleromter acceleration outputs where corrected_accel = raw_accel * accel_scale + accel_offset 11 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 12 | float32[3] accel_offset # accelerometer XYZ offsets in the sensor frame in m/s/s 13 | float32[3] accel_scale # accelerometer XYZ scale factors in the sensor frame 14 | 15 | # Corrections for barometric pressure outputs where corrected_pressure = raw_pressure * pressure_scale + pressure_offset 16 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 17 | float32 baro_offset # barometric pressure offsets in the sensor frame in m/s/s 18 | float32 baro_scale # barometric pressure scale factors in the sensor frame 19 | 20 | uint8 selected_gyro_instance # gyro uORB topic instance for the voted sensor 21 | uint8 selected_accel_instance # accelerometer uORB topic instance for the voted sensor 22 | uint8 selected_baro_instance # barometric pressure uORB topic instance for the voted sensor 23 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorGyro.msg: -------------------------------------------------------------------------------- 1 | uint64 integral_dt # integration time 2 | uint64 error_count 3 | float32 x # angular velocity in the NED X board axis in rad/s 4 | float32 y # angular velocity in the NED Y board axis in rad/s 5 | float32 z # angular velocity in the NED Z board axis in rad/s 6 | float32 x_integral # delta angle in the NED X board axis in rad/s in the integration time frame 7 | float32 y_integral # delta angle in the NED Y board axis in rad/s in the integration time frame 8 | float32 z_integral # delta angle in the NED Z board axis in rad/s in the integration time frame 9 | float32 temperature # temperature in degrees celcius 10 | float32 range_rad_s 11 | float32 scaling 12 | 13 | int16 x_raw 14 | int16 y_raw 15 | int16 z_raw 16 | int16 temperature_raw 17 | 18 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 19 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorMag.msg: -------------------------------------------------------------------------------- 1 | uint64 error_count 2 | float32 x 3 | float32 y 4 | float32 z 5 | float32 range_ga 6 | float32 scaling 7 | float32 temperature 8 | 9 | int16 x_raw 10 | int16 y_raw 11 | int16 z_raw 12 | 13 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 14 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SensorPreflight.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Pre-flight sensor check metrics. These will be zero if the vehicle only has one sensor. 3 | # The topic will not be updated when the vehicle is armed 4 | # 5 | float32 accel_inconsistency_m_s_s # magnitude of maximum acceleration difference between IMU instances in (m/s/s). 6 | float32 gyro_inconsistency_rad_s # magnitude of maximum angular rate difference between IMU instances in (rad/s). 7 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/ServorailStatus.msg: -------------------------------------------------------------------------------- 1 | float32 voltage_v # Servo rail voltage in volts 2 | float32 rssi_v # RSSI pin voltage in volts 3 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SubsystemInfo.msg: -------------------------------------------------------------------------------- 1 | uint64 SUBSYSTEM_TYPE_GYRO = 1 2 | uint64 SUBSYSTEM_TYPE_ACC = 2 3 | uint64 SUBSYSTEM_TYPE_MAG = 4 4 | uint64 SUBSYSTEM_TYPE_ABSPRESSURE = 8 5 | uint64 SUBSYSTEM_TYPE_DIFFPRESSURE = 16 6 | uint64 SUBSYSTEM_TYPE_GPS = 32 7 | uint64 SUBSYSTEM_TYPE_OPTICALFLOW = 64 8 | uint64 SUBSYSTEM_TYPE_CVPOSITION = 128 9 | uint64 SUBSYSTEM_TYPE_LASERPOSITION = 256 10 | uint64 SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 512 11 | uint64 SUBSYSTEM_TYPE_ANGULARRATECONTROL = 1024 12 | uint64 SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 2048 13 | uint64 SUBSYSTEM_TYPE_YAWPOSITION = 4096 14 | uint64 SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384 15 | uint64 SUBSYSTEM_TYPE_POSITIONCONTROL = 32768 16 | uint64 SUBSYSTEM_TYPE_MOTORCONTROL = 65536 17 | uint64 SUBSYSTEM_TYPE_RANGEFINDER = 131072 18 | 19 | bool present 20 | bool enabled 21 | bool ok 22 | uint64 subsystem_type 23 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/SystemPower.msg: -------------------------------------------------------------------------------- 1 | float32 voltage5V_v # peripheral 5V rail voltage 2 | uint8 usb_connected # USB is connected when 1 3 | uint8 brick_valid # brick power is good when 1 4 | uint8 servo_valid # servo power is good when 1 5 | uint8 periph_5V_OC # peripheral overcurrent when 1 6 | uint8 hipower_5V_OC # hi power peripheral overcurrent when 1 7 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/TecsStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 TECS_MODE_NORMAL = 0 2 | uint8 TECS_MODE_UNDERSPEED = 1 3 | uint8 TECS_MODE_TAKEOFF = 2 4 | uint8 TECS_MODE_LAND = 3 5 | uint8 TECS_MODE_LAND_THROTTLELIM = 4 6 | uint8 TECS_MODE_BAD_DESCENT = 5 7 | uint8 TECS_MODE_CLIMBOUT = 6 8 | 9 | 10 | float32 altitudeSp 11 | float32 altitude_filtered 12 | float32 flightPathAngleSp 13 | float32 flightPathAngle 14 | float32 flightPathAngleFiltered 15 | float32 airspeedSp 16 | float32 airspeed_filtered 17 | float32 airspeedDerivativeSp 18 | float32 airspeedDerivative 19 | 20 | float32 totalEnergyError 21 | float32 energyDistributionError 22 | float32 totalEnergyRateError 23 | float32 energyDistributionRateError 24 | 25 | float32 throttle_integ 26 | float32 pitch_integ 27 | 28 | uint8 mode 29 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/TelemetryStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0 2 | uint8 TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO = 1 3 | uint8 TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET = 2 4 | uint8 TELEMETRY_STATUS_RADIO_TYPE_WIRE = 3 5 | uint8 TELEMETRY_STATUS_RADIO_TYPE_USB = 4 6 | uint8 TELEMETRY_STATUS_RADIO_TYPE_IRIDIUM = 5 7 | 8 | uint64 heartbeat_time # Time of last received heartbeat from remote system 9 | uint64 telem_time # Time of last received telemetry status packet, 0 for none 10 | uint8 type # type of the radio hardware 11 | uint8 rssi # local signal strength 12 | uint8 remote_rssi # remote signal strength 13 | uint16 rxerrors # receive errors 14 | uint16 fixed # count of error corrected packets 15 | uint8 noise # background noise level 16 | uint8 remote_noise # remote background noise level 17 | uint8 txbuf # how full the tx buffer is as a percentage 18 | uint8 system_id # system id of the remote system 19 | uint8 component_id # component id of the remote system 20 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/TestMotor.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_MOTOR_OUTPUTS = 8 2 | 3 | uint32 motor_number # number of motor to spin 4 | float32 value # output power, range [0..1] 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/TimeOffset.msg: -------------------------------------------------------------------------------- 1 | uint64 offset_ns # time offset between companion system and PX4, in nanoseconds 2 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/TransponderReport.msg: -------------------------------------------------------------------------------- 1 | uint32 ICAO_address # ICAO address 2 | float64 lat # Latitude, expressed as degrees 3 | float64 lon # Longitude, expressed as degrees 4 | uint8 altitude_type # Type from ADSB_ALTITUDE_TYPE enum 5 | float32 altitude # Altitude(ASL) in meters 6 | float32 heading # Course over ground in radians 7 | float32 hor_velocity # The horizontal velocity in m/s 8 | float32 ver_velocity # The vertical velocity in m/s, positive is up 9 | char[9] callsign # The callsign, 8+null 10 | uint8 emitter_type # Type from ADSB_EMITTER_TYPE enum 11 | uint8 tslc # Time since last communication in seconds 12 | uint16 flags # Flags to indicate various statuses including valid data fields 13 | uint16 squawk # Squawk code 14 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/UavcanParameterRequest.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge request type 2 | uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET 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 # -1 if the param_id field should be used as identifier 6 | uint8 param_type # MAVLink parameter type 7 | int64 int_value # current value if param_type is int-like 8 | float32 real_value # current value if param_type is float-like 9 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/UavcanParameterValue.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge response type 2 | uint8 node_id # UAVCAN node ID mapped from MAVLink component ID 3 | char[17] param_id # MAVLink/UAVCAN parameter name 4 | int16 param_index # parameter index, if known 5 | uint16 param_count # number of parameters exposed by the node 6 | uint8 param_type # MAVLink parameter type 7 | int64 int_value # current value if param_type is int-like 8 | float32 real_value # current value if param_type is float-like 9 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/UlogStream.msg: -------------------------------------------------------------------------------- 1 | # Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA 2 | # mavlink message 3 | 4 | # flags bitmasks 5 | uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked. 6 | # Acked messages are published synchronous: a 7 | # publisher waits for an ack before sending the 8 | # next message 9 | 10 | uint8 length # length of data 11 | uint8 first_message_offset # offset into data where first message starts. This 12 | # can be used for recovery, when a previous message got lost 13 | uint16 sequence # allows determine drops 14 | uint8 flags # see FLAGS_* 15 | uint8[249] data # ulog data 16 | 17 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/UlogStreamAck.msg: -------------------------------------------------------------------------------- 1 | # Ack a previously sent ulog_stream message that had 2 | # the NEED_ACK flag set 3 | 4 | int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms] 5 | int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms 6 | 7 | uint16 sequence 8 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleAttitude.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use 2 | float32 rollspeed # Angular velocity about body north axis (x) in rad/s 3 | float32 pitchspeed # Angular velocity about body east axis (y) in rad/s 4 | float32 yawspeed # Angular velocity about body down axis (z) in rad/s 5 | float32[4] q # Quaternion (NED) 6 | 7 | # TOPICS vehicle_attitude vehicle_attitude_groundtruth 8 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | # For quaternion-based attitude control 19 | float32[4] q_d # Desired quaternion for quaternion control 20 | bool q_d_valid # Set to true if quaternion vector is valid 21 | 22 | float32 thrust # Thrust in Newton the power system should generate 23 | 24 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 25 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 26 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 27 | 28 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 29 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 30 | 31 | bool apply_flaps 32 | 33 | float32 landing_gear 34 | 35 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 36 | # TOPICS vehicle_attitude_setpoint 37 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleCommandAck.msg: -------------------------------------------------------------------------------- 1 | uint8 VEHICLE_RESULT_ACCEPTED = 0 2 | uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1 3 | uint8 VEHICLE_RESULT_DENIED = 2 4 | uint8 VEHICLE_RESULT_UNSUPPORTED = 3 5 | uint8 VEHICLE_RESULT_FAILED = 4 6 | 7 | uint32 ORB_QUEUE_LENGTH = 3 8 | 9 | uint16 command 10 | uint8 result 11 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleControlMode.msg: -------------------------------------------------------------------------------- 1 | 2 | # is set whenever the writing thread stores new data 3 | 4 | bool flag_armed 5 | 6 | bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing 7 | 8 | # XXX needs yet to be set by state machine helper 9 | bool flag_system_hil_enabled 10 | 11 | bool flag_control_manual_enabled # true if manual input is mixed in 12 | bool flag_control_auto_enabled # true if onboard autopilot should act 13 | bool flag_control_offboard_enabled # true if offboard control should be used 14 | bool flag_control_rates_enabled # true if rates are stabilized 15 | bool flag_control_attitude_enabled # true if attitude stabilization is mixed in 16 | bool flag_control_rattitude_enabled # true if rate/attitude stabilization is enabled 17 | bool flag_control_force_enabled # true if force control is mixed in 18 | bool flag_control_acceleration_enabled # true if acceleration is controlled 19 | bool flag_control_velocity_enabled # true if horizontal velocity (implies direction) is controlled 20 | bool flag_control_position_enabled # true if position is controlled 21 | bool flag_control_altitude_enabled # true if altitude is controlled 22 | bool flag_control_climb_rate_enabled # true if climb rate is controlled 23 | bool flag_control_termination_enabled # true if flighttermination is enabled 24 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleForceSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Definition of force (NED) setpoint uORB topic. Typically this can be used 2 | # by a position control app together with an attitude control app. 3 | 4 | 5 | float32 x # in N NED 6 | float32 y # in N NED 7 | float32 z # in N NED 8 | float32 yaw # right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw) 9 | -------------------------------------------------------------------------------- /px4_msgs_ros1/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 | uint64 time_utc_usec # GPS UTC timestamp, (microseconds) 8 | float64 lat # Latitude, (degrees) 9 | float64 lon # Longitude, (degrees) 10 | float32 alt # Altitude AMSL, (meters) 11 | float64[2] delta_lat_lon # Reset delta for horizontal position coordinates 12 | float32 delta_alt # Reset delta for altitude 13 | uint8 lat_lon_reset_counter # Counter for reset events on horizontal position coordinates 14 | uint8 alt_reset_counter # Counter for reset events on altitude 15 | float32 vel_n # North velocity in NED earth-fixed frame, (metres/sec) 16 | float32 vel_e # East velocity in NED earth-fixed frame, (metres/sec) 17 | float32 vel_d # Down velocity in NED earth-fixed frame, (metres/sec) 18 | float32 yaw # Euler yaw angle relative to NED earth-fixed frame, -PI..+PI, (radians) 19 | float32 eph # Standard deviation of horizontal position error, (metres) 20 | float32 epv # Standard deviation of vertical position error, (metres) 21 | float32 terrain_alt # Terrain altitude WGS84, (metres) 22 | bool terrain_alt_valid # Terrain altitude estimate is valid 23 | bool dead_reckoning # True if this position is estimated through dead-reckoning 24 | float32 pressure_alt # Pressure altitude AMSL, (metres) 25 | 26 | # TOPICS vehicle_global_position vehicle_global_position_groundtruth 27 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleGlobalVelocitySetpoint.msg: -------------------------------------------------------------------------------- 1 | # Velocity setpoint in NED frame 2 | float32 vx # in m/s NED 3 | float32 vy # in m/s NED 4 | float32 vz # in m/s NED 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleGpsPosition.msg: -------------------------------------------------------------------------------- 1 | # GPS position in WGS84 coordinates. 2 | # the auto-generated field 'timestamp' is for the position & velocity (microseconds) 3 | int32 lat # Latitude in 1E-7 degrees 4 | int32 lon # Longitude in 1E-7 degrees 5 | int32 alt # Altitude in 1E-3 meters above MSL, (millimetres) 6 | int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres) 7 | 8 | float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec) 9 | float32 c_variance_rad # GPS course accuracy estimate, (radians) 10 | uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 11 | 12 | float32 eph # GPS horizontal position accuracy (metres) 13 | float32 epv # GPS vertical position accuracy (metres) 14 | 15 | float32 hdop # Horizontal dilution of precision 16 | float32 vdop # Vertical dilution of precision 17 | 18 | int32 noise_per_ms # GPS noise per millisecond 19 | int32 jamming_indicator # indicates jamming is occurring 20 | 21 | float32 vel_m_s # GPS ground speed, (metres/sec) 22 | float32 vel_n_m_s # GPS North velocity, (metres/sec) 23 | float32 vel_e_m_s # GPS East velocity, (metres/sec) 24 | float32 vel_d_m_s # GPS Down velocity, (metres/sec) 25 | float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians) 26 | bool vel_ned_valid # True if NED velocity is valid 27 | 28 | int32 timestamp_time_relative # timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds) 29 | 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 30 | 31 | uint8 satellites_used # Number of satellites used 32 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleLandDetected.msg: -------------------------------------------------------------------------------- 1 | bool landed # true if vehicle is currently landed on the ground 2 | bool freefall # true if vehicle is currently in free-fall 3 | bool ground_contact # true if vehicle has ground contact but is not landed 4 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleLocalPositionSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Local position setpoint in NED frame 2 | 3 | float32 x # in meters NED 4 | float32 y # in meters NED 5 | float32 z # in meters NED 6 | float32 yaw # in radians NED -PI..+PI 7 | float32 vx # in meters/sec 8 | float32 vy # in meters/sec 9 | float32 vz # in meters/sec 10 | float32 acc_x # in meters/(sec*sec) 11 | float32 acc_y # in meters/(sec*sec) 12 | float32 acc_z # in meters/(sec*sec) 13 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VehicleRoi.msg: -------------------------------------------------------------------------------- 1 | # Vehicle Region Of Interest (ROI) 2 | 3 | uint8 VEHICLE_ROI_NONE = 0 # No region of interest | 4 | uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | 5 | uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | 6 | uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | 7 | uint8 VEHICLE_ROI_TARGET = 4 # Point toward target 8 | uint8 VEHICLE_ROI_ENUM_END = 5 9 | 10 | uint8 mode # ROI mode (see above) 11 | uint32 mission_seq # mission sequence to point to 12 | uint32 target_seq # target sequence to point to 13 | float64 lat # Latitude to point to 14 | float64 lon # Longitude to point to 15 | float32 alt # Altitude to point to 16 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VisionPositionEstimate.msg: -------------------------------------------------------------------------------- 1 | uint32 id # ID of the estimator, commonly the component ID of the incoming message 2 | 3 | uint64 timestamp_received # timestamp when the estimate was received 4 | 5 | float32 x # X position in meters in NED earth-fixed frame 6 | float32 y # Y position in meters in NED earth-fixed frame 7 | float32 z # Z position in meters in NED earth-fixed frame (negative altitude) 8 | 9 | float32 vx # X velocity in meters per second in NED earth-fixed frame 10 | float32 vy # Y velocity in meters per second in NED earth-fixed frame 11 | float32 vz # Z velocity in meters per second in NED earth-fixed frame 12 | 13 | float32[4] q # Estimated attitude as quaternion 14 | 15 | float32 pos_err # position error 1-std for each axis (metres) 16 | float32 ang_err # angular error 1-std for each axis (rad) 17 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/VtolVehicleStatus.msg: -------------------------------------------------------------------------------- 1 | # VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE 2 | uint8 VEHICLE_VTOL_STATE_UNDEFINED = 0 3 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_FW = 1 4 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2 5 | uint8 VEHICLE_VTOL_STATE_MC = 3 6 | uint8 VEHICLE_VTOL_STATE_FW = 4 7 | uint8 VEHICLE_VTOL_STATE_EXTERNAL = 5 8 | 9 | bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode 10 | bool vtol_in_trans_mode 11 | bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW 12 | bool vtol_transition_failsafe # vtol in transition failsafe mode 13 | bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode 14 | float32 airspeed_tot # Estimated airspeed over control surfaces 15 | -------------------------------------------------------------------------------- /px4_msgs_ros1/msg/WindEstimate.msg: -------------------------------------------------------------------------------- 1 | float32 windspeed_north # Wind component in north / X direction 2 | float32 windspeed_east # Wind component in east / Y direction 3 | float32 covariance_north # Uncertainty - set to zero (no uncertainty) if not estimated 4 | float32 covariance_east # Uncertainty - set to zero (no uncertainty) if not estimated 5 | -------------------------------------------------------------------------------- /px4_msgs_ros1/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | px4_msgs 4 | 0.0.0 5 | The px4_msgs package 6 | 7 | 8 | 9 | 10 | vmonge 11 | 12 | Apache License, Version 2.0 13 | 14 | catkin 15 | 16 | message_generation 17 | 18 | message_runtime 19 | 20 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ActuatorArmed.msg: -------------------------------------------------------------------------------- 1 | 2 | bool armed # Set to true if system is armed 3 | bool prearmed # Set to true if the actuator safety is disabled but motors are not armed 4 | bool ready_to_arm # Set to true if system is ready to be armed 5 | bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL) 6 | bool manual_lockdown # Set to true if manual throttle kill switch is engaged 7 | bool force_failsafe # Set to true if the actuators are forced to the failsafe position 8 | bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics 9 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ActuatorControls.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATOR_CONTROLS = 8 2 | uint8 NUM_ACTUATOR_CONTROL_GROUPS = 4 3 | uint8 INDEX_ROLL = 0 4 | uint8 INDEX_PITCH = 1 5 | uint8 INDEX_YAW = 2 6 | uint8 INDEX_THROTTLE = 3 7 | uint8 INDEX_FLAPS = 4 8 | uint8 INDEX_SPOILERS = 5 9 | uint8 INDEX_AIRBRAKES = 6 10 | uint8 INDEX_LANDING_GEAR = 7 11 | uint8 GROUP_INDEX_ATTITUDE = 0 12 | uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1 13 | uint64 timestamp_sample # the timestamp the data this control response is based on was sampled 14 | float32[8] control 15 | 16 | # TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3 17 | # TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc 18 | 19 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ActuatorDirect.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATORS_DIRECT = 16 2 | uint32 nvalues # number of valid values 3 | float32[16] values # actuator values, from -1 to 1 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ActuatorOutputs.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATOR_OUTPUTS = 16 2 | uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking 3 | uint32 noutputs # valid outputs 4 | float32[16] output # output data, in natural output units 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/AdcReport.msg: -------------------------------------------------------------------------------- 1 | int16[8] channel_id # ADC channel IDs, negative for non-existent 2 | float32[8] channel_value # ADC channel value in volt, valid if channel ID is positive 3 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/Airspeed.msg: -------------------------------------------------------------------------------- 1 | float32 indicated_airspeed_m_s # indicated airspeed in meters per second, -1 if unknown 2 | float32 true_airspeed_m_s # true filtered airspeed in meters per second, -1 if unknown 3 | float32 true_airspeed_unfiltered_m_s # true airspeed in meters per second, -1 if unknown 4 | float32 air_temperature_celsius # air temperature in degrees celsius, -1000 if unknown 5 | float32 confidence # confidence value from 0 to 1 for this sensor 6 | float32 differential_pressure_filtered_pa # filtered differential pressure, can be negative 7 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/AttPosMocap.msg: -------------------------------------------------------------------------------- 1 | uint32 id # ID of the estimator, commonly the component ID of the incoming message 2 | 3 | uint64 timestamp_received # timestamp when the estimate was received 4 | 5 | float32[4] q # Estimated attitude as quaternion 6 | 7 | float32 x # X position in meters in NED earth-fixed frame 8 | float32 y # Y position in meters in NED earth-fixed frame 9 | float32 z # Z position in meters in NED earth-fixed frame (negative altitude) 10 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/BatteryStatus.msg: -------------------------------------------------------------------------------- 1 | float32 voltage_v # Battery voltage in volts, 0 if unknown 2 | float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown 3 | float32 current_a # Battery current in amperes, -1 if unknown 4 | float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown 5 | float32 discharged_mah # Discharged amount in mAh, -1 if unknown 6 | float32 remaining # From 1 to 0, -1 if unknown 7 | float32 scale # Power scaling factor, >= 1, or -1 if unknown 8 | int32 cell_count # Number of cells 9 | bool connected # Wether or not a battery is connected 10 | #bool is_powering_off # Power off event imminent indication, false if unknown 11 | 12 | 13 | uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active 14 | uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage 15 | uint8 BATTERY_WARNING_CRITICAL = 2 # alerting of critical voltage 16 | 17 | uint8 warning # current battery warning 18 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/CameraTrigger.msg: -------------------------------------------------------------------------------- 1 | 2 | uint32 seq # Image sequence 3 | 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/CollisionReport.msg: -------------------------------------------------------------------------------- 1 | uint8 src 2 | uint32 id 3 | uint8 action 4 | uint8 threat_level 5 | float32 time_to_minimum_delta 6 | float32 altitude_minimum_delta 7 | float32 horizontal_minimum_delta 8 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/CommanderState.msg: -------------------------------------------------------------------------------- 1 | # Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link. 2 | uint8 MAIN_STATE_MANUAL = 0 3 | uint8 MAIN_STATE_ALTCTL = 1 4 | uint8 MAIN_STATE_POSCTL = 2 5 | uint8 MAIN_STATE_AUTO_MISSION = 3 6 | uint8 MAIN_STATE_AUTO_LOITER = 4 7 | uint8 MAIN_STATE_AUTO_RTL = 5 8 | uint8 MAIN_STATE_ACRO = 6 9 | uint8 MAIN_STATE_OFFBOARD = 7 10 | uint8 MAIN_STATE_STAB = 8 11 | uint8 MAIN_STATE_RATTITUDE = 9 12 | uint8 MAIN_STATE_AUTO_TAKEOFF = 10 13 | uint8 MAIN_STATE_AUTO_LAND = 11 14 | uint8 MAIN_STATE_AUTO_FOLLOW_TARGET = 12 15 | uint8 MAIN_STATE_MAX = 13 16 | 17 | 18 | uint8 main_state # main state machine 19 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ControlState.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message CONTROL_SYSTEM_STATE, but for onboard use */ 2 | uint8 AIRSPD_MODE_MEAS = 0 # airspeed is measured airspeed from sensor 3 | uint8 AIRSPD_MODE_EST = 1 # airspeed is estimated by body velocity 4 | uint8 AIRSPD_MODE_DISABLED = 2 # airspeed is disabled 5 | 6 | float32 x_acc # X acceleration in body frame 7 | float32 y_acc # Y acceleration in body frame 8 | float32 z_acc # Z acceleration in body frame 9 | float32 x_vel # X velocity in body frame 10 | float32 y_vel # Y velocity in body frame 11 | float32 z_vel # Z velocity in body frame 12 | float32 x_pos # X position in local earth frame 13 | float32 y_pos # Y position in local earth frame 14 | float32 z_pos # z position in local earth frame 15 | float32 airspeed # Airspeed, estimated 16 | bool airspeed_valid # False: Non-finite values or non-updating sensor 17 | float32[3] vel_variance # Variance in body velocity estimate 18 | float32[3] pos_variance # Variance in local position estimate 19 | float32[4] q # Attitude Quaternion 20 | float32[4] delta_q_reset # Amount by which quaternion has changed during last reset 21 | uint8 quat_reset_counter # Quaternion reset counter 22 | float32 roll_rate # Roll body angular rate (rad/s, x forward/y right/z down) - corrected for bias 23 | float32 pitch_rate # Pitch body angular rate (rad/s, x forward/y right/z down) - corrected for bias 24 | float32 yaw_rate # Yaw body angular rate (rad/s, x forward/y right/z down) - corrected for bias 25 | float32 horz_acc_mag # low pass filtered magnitude of the horizontal acceleration 26 | float32 roll_rate_bias # Roll body angular rate bias (rad/s, x forward) - subtract from uncorrected gyro data 27 | float32 pitch_rate_bias # Pitch body angular rate bias (rad/s, y right) - subtract from uncorrected gyro data 28 | float32 yaw_rate_bias # Yaw body angular rate bias (rad/s, z down) - subtract from uncorrected gyro data 29 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/Cpuload.msg: -------------------------------------------------------------------------------- 1 | float32 load # processor load from 0 to 1 2 | float32 ram_usage # RAM usage from 0 to 1 3 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/DebugKeyValue.msg: -------------------------------------------------------------------------------- 1 | uint32 timestamp_ms # in milliseconds since system start 2 | int8[10] key # max. 10 characters as key / name 3 | float32 value # the value to send as debug output 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/DifferentialPressure.msg: -------------------------------------------------------------------------------- 1 | uint64 error_count # Number of errors detected by driver 2 | float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative) 3 | float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading 4 | float32 max_differential_pressure_pa # Maximum differential pressure reading 5 | float32 temperature # Temperature provided by sensor, -1000.0f if unknown 6 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/DistanceSensor.msg: -------------------------------------------------------------------------------- 1 | # DISTANCE_SENSOR message data 2 | 3 | 4 | float32 min_distance # Minimum distance the sensor can measure (in m) 5 | float32 max_distance # Maximum distance the sensor can measure (in m) 6 | float32 current_distance # Current distance reading (in m) 7 | float32 covariance # Measurement covariance (in m), 0 for unknown / invalid readings 8 | 9 | uint8 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 | uint8 id # Onboard ID of the sensor 16 | 17 | uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum 18 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/Ekf2Innovations.msg: -------------------------------------------------------------------------------- 1 | float32[6] vel_pos_innov # velocity and position innovations 2 | float32[3] mag_innov # earth magnetic field innovations 3 | float32 heading_innov # heading innovation 4 | float32 airspeed_innov # airspeed innovation 5 | float32 beta_innov # synthetic sideslip innovation 6 | float32[2] flow_innov # flow innovation 7 | float32 hagl_innov # innovation from the terrain estimator for the height above ground level measurement (m) 8 | float32[6] vel_pos_innov_var # velocity and position innovation variances 9 | float32[3] mag_innov_var # earth magnetic field innovation variance 10 | float32 heading_innov_var # heading innovation variance 11 | float32 airspeed_innov_var # Airspeed innovation variance 12 | float32 beta_innov_var # synthetic sideslip innovation variance 13 | float32[2] flow_innov_var # flow innovation variance 14 | float32 hagl_innov_var # innovation variance from the terrain estimator for the height above ground level measurement (m^2) 15 | float32[3] output_tracking_error # return a vector containing the output predictor angular, velocity and position tracking error magnitudes (rad), (m/s), (m) 16 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/EscReport.msg: -------------------------------------------------------------------------------- 1 | uint8 esc_vendor # Vendor of current ESC 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 | float32 esc_setpoint # setpoint of current ESC 8 | uint16 esc_setpoint_raw # setpoint of current ESC (Value sent to ESC) 9 | uint16 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver) 10 | uint16 esc_version # Version of current ESC - if supported 11 | uint16 esc_state # State of ESC - depend on Vendor 12 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/EscStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs 2 | 3 | uint8 ESC_VENDOR_GENERIC = 0 # generic ESC 4 | uint8 ESC_VENDOR_MIKROKOPTER = 1 # Mikrokopter 5 | uint8 ESC_VENDOR_GRAUPNER_HOTT = 2 # Graupner HoTT ESC 6 | uint8 ESC_VENDOR_TAP = 3 # TAP ESC 7 | 8 | uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC 9 | uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC 10 | uint8 ESC_CONNECTION_TYPE_ONESHOOT = 2 # One Shoot PPM 11 | uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C 12 | uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus 13 | 14 | uint16 counter # incremented by the writing thread everytime new data is stored 15 | 16 | uint8 esc_count # number of connected ESCs 17 | uint8 esc_connectiontype # how ESCs connected to the system 18 | 19 | esc_report[8] esc 20 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/Fence.msg: -------------------------------------------------------------------------------- 1 | uint8 GEOFENCE_MAX_VERTICES = 16 2 | 3 | uint32 count # number of actual vertices 4 | fence_vertex[16] vertices # geofence positions 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/FenceVertex.msg: -------------------------------------------------------------------------------- 1 | float32 lat # latitude in degrees, worst case float precision gives us 2 meter resolution at the equator 2 | float32 lon # longitude in degrees, worst case float precision gives us 2 meter resolution at the equator 3 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/FilteredBottomFlow.msg: -------------------------------------------------------------------------------- 1 | # Filtered bottom flow in bodyframe. 2 | 3 | float32 sumx # Integrated bodyframe x flow in meters 4 | float32 sumy # Integrated bodyframe y flow in meters 5 | 6 | float32 vx # Flow bodyframe x speed, m/s 7 | float32 vy # Flow bodyframe y Speed, m/s 8 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/FollowTarget.msg: -------------------------------------------------------------------------------- 1 | float64 lat # target position (deg * 1e7) 2 | float64 lon # target position (deg * 1e7) 3 | float32 alt # target position 4 | float32 vy # target vel in y 5 | float32 vx # target vel in x 6 | float32 vz # target vel in z 7 | uint8 est_cap # target reporting capabilities 8 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/FwPosCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | float32 nav_roll 2 | float32 nav_pitch 3 | float32 nav_bearing 4 | 5 | float32 target_bearing 6 | float32 wp_dist 7 | float32 xtrack_error 8 | float32 turn_distance # the optimal distance to a waypoint to switch to the next 9 | 10 | float32 landing_horizontal_slope_displacement 11 | float32 landing_slope_angle_rad 12 | float32 landing_flare_length 13 | bool abort_landing 14 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/FwVirtualAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame 19 | bool R_valid # Set to true if rotation matrix is valid 20 | 21 | # For quaternion-based attitude control 22 | float32[4] q_d # Desired quaternion for quaternion control 23 | bool q_d_valid # Set to true if quaternion vector is valid 24 | float32[4] q_e # Attitude error in quaternion 25 | bool q_e_valid # Set to true if quaternion error vector is valid 26 | 27 | float32 thrust # Thrust in Newton the power system should generate 28 | 29 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 30 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 31 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 32 | 33 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 34 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 35 | 36 | bool apply_flaps 37 | 38 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 39 | # TOPICS fw_virtual_attitude_setpoint 40 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/FwVirtualRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/GeofenceResult.msg: -------------------------------------------------------------------------------- 1 | uint8 GF_ACTION_NONE = 0 # no action on geofence violation 2 | uint8 GF_ACTION_WARN = 1 # critical mavlink message 3 | uint8 GF_ACTION_LOITER = 2 # switch to AUTO|LOITER 4 | uint8 GF_ACTION_RTL = 3 # switch to AUTO|RTL 5 | uint8 GF_ACTION_TERMINATE = 4 # flight termination 6 | 7 | bool geofence_violated # true if the geofence is violated 8 | uint8 geofence_action # action to take when geofence is violated -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/GpsDump.msg: -------------------------------------------------------------------------------- 1 | # This message is used to dump the raw gps communication to the log. 2 | # Set the parameter GPS_DUMP_COMM to 1 to use this. 3 | 4 | uint8 len # length of data, MSB bit set = message to the gps device, 5 | # clear = message from the device 6 | uint8[79] data # data to write to the log 7 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/GpsInjectData.msg: -------------------------------------------------------------------------------- 1 | uint8 len # length of data 2 | uint8 flags # LSB: 1=fragmented 3 | uint8[182] data # data to write to GPS device (RTCM message) 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/HomePosition.msg: -------------------------------------------------------------------------------- 1 | # GPS home position in WGS84 coordinates. 2 | 3 | float64 lat # Latitude in degrees 4 | float64 lon # Longitude in degrees 5 | float32 alt # Altitude in meters (AMSL) 6 | 7 | float32 x # X coordinate in meters 8 | float32 y # Y coordinate in meters 9 | float32 z # Z coordinate in meters 10 | 11 | float32 yaw # Yaw angle in radians 12 | float32 direction_x # Takeoff direction in NED X 13 | float32 direction_y # Takeoff direction in NED Y 14 | float32 direction_z # Takeoff direction in NED Z 15 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/LogMessage.msg: -------------------------------------------------------------------------------- 1 | # A logging message, output with PX4_{WARN,ERR,INFO} 2 | 3 | uint8 severity # log level (same as in the linux kernel, starting with 0) 4 | uint8[127] text 5 | 6 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/LowStack.msg: -------------------------------------------------------------------------------- 1 | uint8 MAX_REPORT_TASK_NAME_LEN = 16 2 | 3 | uint16 stack_free 4 | uint8[16] task_name 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/MavlinkLog.msg: -------------------------------------------------------------------------------- 1 | 2 | uint8[50] text 3 | uint8 severity # log level (same as in the linux kernel, starting with 0) 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/McAttCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | 2 | float32 roll_rate_integ # roll rate inegrator 3 | float32 pitch_rate_integ # pitch rate integrator 4 | float32 yaw_rate_integ # yaw rate integrator 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/McVirtualAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame 19 | bool R_valid # Set to true if rotation matrix is valid 20 | 21 | # For quaternion-based attitude control 22 | float32[4] q_d # Desired quaternion for quaternion control 23 | bool q_d_valid # Set to true if quaternion vector is valid 24 | float32[4] q_e # Attitude error in quaternion 25 | bool q_e_valid # Set to true if quaternion error vector is valid 26 | 27 | float32 thrust # Thrust in Newton the power system should generate 28 | 29 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 30 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 31 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 32 | 33 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 34 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 35 | 36 | bool apply_flaps 37 | 38 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 39 | # TOPICS mc_virtual_attitude_setpoint 40 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/McVirtualRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/Mission.msg: -------------------------------------------------------------------------------- 1 | int32 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1 2 | uint32 count # count of the missions stored in the dataman 3 | int32 current_seq # default -1, start at the one changed latest 4 | 5 | # TOPICS mission offboard_mission onboard_mission 6 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/MissionResult.msg: -------------------------------------------------------------------------------- 1 | uint32 instance_count # Instance count of this mission. Increments monotonically whenever the mission is modified 2 | uint32 seq_reached # Sequence of the mission item which has been reached 3 | uint32 seq_current # Sequence of the current mission item 4 | uint32 seq_total # Total number of mission items 5 | bool valid # true if mission is valid 6 | bool warning # true if mission is valid, but has potentially problematic items leading to safety warnings 7 | bool reached # true if mission has been reached 8 | bool finished # true if mission has been completed 9 | bool stay_in_failsafe # true if the commander should not switch out of the failsafe mode 10 | bool flight_termination # true if the navigator demands a flight termination from the commander app 11 | bool item_do_jump_changed # true if the number of do jumps remaining has changed 12 | uint32 item_changed_index # indicate which item has changed 13 | uint32 item_do_jump_remaining # set to the number of do jumps remaining for that item 14 | bool mission_failure # true if the mission cannot continue or be completed for some reason 15 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/MountOrientation.msg: -------------------------------------------------------------------------------- 1 | float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad 2 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/MultirotorMotorLimits.msg: -------------------------------------------------------------------------------- 1 | uint16 saturation_status # Integer bit mask indicating which axes in the control mixer are saturated 2 | # 0 - True if any motor is saturated at the upper limit 3 | # 1 - True if any motor is saturated at the lower limit 4 | # 2 - True if a positive roll increment will increase motor saturation 5 | # 3 - True if negative roll increment will increase motor saturation 6 | # 4 - True if positive pitch increment will increase motor saturation 7 | # 5 - True if negative pitch increment will increase motor saturation 8 | # 6 - True if positive yaw increment will increase motor saturation 9 | # 7 - True if negative yaw increment will increase motor saturation 10 | # 8 - True if positive thrust increment will increase motor saturation 11 | # 9 - True if negative thrust increment will increase motor saturation 12 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/OffboardControlMode.msg: -------------------------------------------------------------------------------- 1 | # Off-board control mode 2 | 3 | bool ignore_thrust 4 | bool ignore_attitude 5 | bool ignore_bodyrate 6 | bool ignore_position 7 | bool ignore_velocity 8 | bool ignore_acceleration_force 9 | bool ignore_alt_hold 10 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/OpticalFlow.msg: -------------------------------------------------------------------------------- 1 | # Optical flow in XYZ body frame in SI units. 2 | # @see http://en.wikipedia.org/wiki/International_System_of_Units 3 | 4 | uint8 sensor_id # id of the sensor emitting the flow value 5 | float32 pixel_flow_x_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the X body axis 6 | float32 pixel_flow_y_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the Y body axis 7 | float32 gyro_x_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the X body axis 8 | float32 gyro_y_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the Y body axis 9 | float32 gyro_z_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the Z body axis 10 | float32 ground_distance_m # Altitude / distance to ground in meters 11 | uint32 integration_timespan # accumulation timespan in microseconds 12 | uint32 time_since_last_sonar_update # time since last sonar update in microseconds 13 | uint16 frame_count_since_last_readout # number of accumulated frames in timespan 14 | int16 gyro_temperature # Temperature * 100 in centi-degrees Celsius 15 | uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: maximum quality 16 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/OutputPwm.msg: -------------------------------------------------------------------------------- 1 | uint8 PWM_OUTPUT_MAX_CHANNELS = 16 2 | uint16[16] values 3 | uint32 channel_count 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ParameterUpdate.msg: -------------------------------------------------------------------------------- 1 | bool saved # wether the change has already been saved to disk 2 | -------------------------------------------------------------------------------- /px4_msgs_ros2/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 | px4/position_setpoint previous 5 | px4/position_setpoint current 6 | px4/position_setpoint next 7 | 8 | uint8 nav_state # report the navigation state 9 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/PwmInput.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 error_count 3 | uint32 pulse_width # Pulse width, timer counts 4 | uint32 period # Period, timer counts 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/QshellReq.msg: -------------------------------------------------------------------------------- 1 | int32[100] string 2 | uint64 MAX_STRLEN = 100 3 | uint64 strlen 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/RcChannels.msg: -------------------------------------------------------------------------------- 1 | int32 RC_CHANNELS_FUNCTION_MAX=21 2 | uint8 RC_CHANNELS_FUNCTION_THROTTLE=0 3 | uint8 RC_CHANNELS_FUNCTION_ROLL=1 4 | uint8 RC_CHANNELS_FUNCTION_PITCH=2 5 | uint8 RC_CHANNELS_FUNCTION_YAW=3 6 | uint8 RC_CHANNELS_FUNCTION_MODE=4 7 | uint8 RC_CHANNELS_FUNCTION_RETURN=5 8 | uint8 RC_CHANNELS_FUNCTION_POSCTL=6 9 | uint8 RC_CHANNELS_FUNCTION_LOITER=7 10 | uint8 RC_CHANNELS_FUNCTION_OFFBOARD=8 11 | uint8 RC_CHANNELS_FUNCTION_ACRO=9 12 | uint8 RC_CHANNELS_FUNCTION_FLAPS=10 13 | uint8 RC_CHANNELS_FUNCTION_AUX_1=11 14 | uint8 RC_CHANNELS_FUNCTION_AUX_2=12 15 | uint8 RC_CHANNELS_FUNCTION_AUX_3=13 16 | uint8 RC_CHANNELS_FUNCTION_AUX_4=14 17 | uint8 RC_CHANNELS_FUNCTION_AUX_5=15 18 | uint8 RC_CHANNELS_FUNCTION_PARAM_1=16 19 | uint8 RC_CHANNELS_FUNCTION_PARAM_2=17 20 | uint8 RC_CHANNELS_FUNCTION_PARAM_3_5=18 21 | uint8 RC_CHANNELS_FUNCTION_RATTITUDE=19 22 | uint8 RC_CHANNELS_FUNCTION_KILLSWITCH=20 23 | uint8 RC_CHANNELS_FUNCTION_TRANSITION=21 24 | uint8 RC_CHANNELS_FUNCTION_GEAR=22 25 | uint8 RC_CHANNELS_FUNCTION_ARMSWITCH=23 26 | 27 | uint64 timestamp_last_valid # Timestamp of last valid RC signal 28 | float32[18] channels # Scaled to -1..1 (throttle: 0..1) 29 | uint8 channel_count # Number of valid channels 30 | int8[24] function # Functions mapping 31 | uint8 rssi # Receive signal strength indicator (0-100) 32 | bool signal_lost # Control signal lost, should be checked together with topic timeout 33 | uint32 frame_drop_count # Number of dropped frames 34 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/RcParameterMap.msg: -------------------------------------------------------------------------------- 1 | uint8 RC_PARAM_MAP_NCHAN = 3 # This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h 2 | uint8 PARAM_ID_LEN = 16 # corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 3 | 4 | bool[3] valid #true for RC-Param channels which are mapped to a param 5 | int32[3] param_index # corresponding param index, this field is ignored if set to -1, in this case param_id will be used 6 | char[51] param_id # MAP_NCHAN * (ID_LEN + 1) chars, corresponding param id, null terminated 7 | float32[3] scale # scale to map the RC input [-1, 1] to a parameter value 8 | float32[3] value0 # initial value around which the parameter value is changed 9 | float32[3] value_min # minimal parameter value 10 | float32[3] value_max # minimal parameter value 11 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/Safety.msg: -------------------------------------------------------------------------------- 1 | bool safety_switch_available # Set to true if a safety switch is connected 2 | bool safety_off # Set to true if safety is off 3 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SatelliteInfo.msg: -------------------------------------------------------------------------------- 1 | uint8 SAT_INFO_MAX_SATELLITES = 20 2 | 3 | uint8 count # Number of satellites in satellite info 4 | uint8[20] svid # Space vehicle ID [1..255], see scheme below 5 | uint8[20] used # 0: Satellite not used, 1: used for navigation 6 | uint8[20] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite 7 | uint8[20] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg. 8 | uint8[20] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. 9 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorAccel.msg: -------------------------------------------------------------------------------- 1 | uint64 integral_dt # integration time 2 | uint64 error_count 3 | float32 x # acceleration in the NED X board axis in m/s^2 4 | float32 y # acceleration in the NED Y board axis in m/s^2 5 | float32 z # acceleration in the NED Z board axis in m/s^2 6 | float32 x_integral # velocity in the NED X board axis in m/s over the integration time frame 7 | float32 y_integral # velocity in the NED Y board axis in m/s over the integration time frame 8 | float32 z_integral # velocity in the NED Z board axis in m/s over the integration time frame 9 | float32 temperature # temperature in degrees celsius 10 | float32 range_m_s2 # range in m/s^2 (+- this value) 11 | float32 scaling 12 | 13 | int16 x_raw 14 | int16 y_raw 15 | int16 z_raw 16 | int16 temperature_raw 17 | 18 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 19 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorBaro.msg: -------------------------------------------------------------------------------- 1 | float32 pressure # static pressure measurement in millibar 2 | float32 altitude # ISA pressure altitude in meters 3 | float32 temperature # static temperature measurement in deg C 4 | uint64 error_count 5 | uint32 device_id # Sensor ID that must be unique for each baro sensor and must not change 6 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorCombined.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor readings in SI-unit form. 3 | # 4 | # These fields are scaled and offset-compensated where possible and do not 5 | # change with board revisions and sensor updates. 6 | # 7 | 8 | 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 9 | 10 | 11 | # gyro timstamp is equal to the timestamp of the message 12 | float32[3] gyro_rad # average angular rate measured in the XYZ body frame in rad/s over the last gyro sampling period 13 | float32 gyro_integral_dt # gyro measurement sampling period in s 14 | 15 | int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp 16 | float32[3] accelerometer_m_s2 # average value acceleration measured in the XYZ body frame in m/s/s over the last accelerometer sampling period 17 | float32 accelerometer_integral_dt # accelerometer measurement sampling period in s 18 | 19 | int32 magnetometer_timestamp_relative # timestamp + magnetometer_timestamp_relative = Magnetometer timestamp 20 | float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss 21 | 22 | int32 baro_timestamp_relative # timestamp + baro_timestamp_relative = Barometer timestamp 23 | float32 baro_alt_meter # Altitude, already temp. comp. 24 | float32 baro_temp_celcius # Temperature in degrees celsius 25 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorCorrection.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor corrections in SI-unit form for the voted sensor 3 | # 4 | 5 | # Corrections for gyro angular rate outputs where corrected_rate = raw_rate * gyro_scale + gyro_offset 6 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 7 | float32[3] gyro_offset # gyro XYZ offsets in the sensor frame in rad/s 8 | float32[3] gyro_scale # gyro XYZ scale factors in the sensor frame 9 | 10 | # Corrections for acceleromter acceleration outputs where corrected_accel = raw_accel * accel_scale + accel_offset 11 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 12 | float32[3] accel_offset # accelerometer XYZ offsets in the sensor frame in m/s/s 13 | float32[3] accel_scale # accelerometer XYZ scale factors in the sensor frame 14 | 15 | # Corrections for barometric pressure outputs where corrected_pressure = raw_pressure * pressure_scale + pressure_offset 16 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 17 | float32 baro_offset # barometric pressure offsets in the sensor frame in m/s/s 18 | float32 baro_scale # barometric pressure scale factors in the sensor frame 19 | 20 | uint8 selected_gyro_instance # gyro uORB topic instance for the voted sensor 21 | uint8 selected_accel_instance # accelerometer uORB topic instance for the voted sensor 22 | uint8 selected_baro_instance # barometric pressure uORB topic instance for the voted sensor 23 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorGyro.msg: -------------------------------------------------------------------------------- 1 | uint64 integral_dt # integration time 2 | uint64 error_count 3 | float32 x # angular velocity in the NED X board axis in rad/s 4 | float32 y # angular velocity in the NED Y board axis in rad/s 5 | float32 z # angular velocity in the NED Z board axis in rad/s 6 | float32 x_integral # delta angle in the NED X board axis in rad/s in the integration time frame 7 | float32 y_integral # delta angle in the NED Y board axis in rad/s in the integration time frame 8 | float32 z_integral # delta angle in the NED Z board axis in rad/s in the integration time frame 9 | float32 temperature # temperature in degrees celcius 10 | float32 range_rad_s 11 | float32 scaling 12 | 13 | int16 x_raw 14 | int16 y_raw 15 | int16 z_raw 16 | int16 temperature_raw 17 | 18 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 19 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorMag.msg: -------------------------------------------------------------------------------- 1 | uint64 error_count 2 | float32 x 3 | float32 y 4 | float32 z 5 | float32 range_ga 6 | float32 scaling 7 | float32 temperature 8 | 9 | int16 x_raw 10 | int16 y_raw 11 | int16 z_raw 12 | 13 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 14 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SensorPreflight.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Pre-flight sensor check metrics. These will be zero if the vehicle only has one sensor. 3 | # The topic will not be updated when the vehicle is armed 4 | # 5 | float32 accel_inconsistency_m_s_s # magnitude of maximum acceleration difference between IMU instances in (m/s/s). 6 | float32 gyro_inconsistency_rad_s # magnitude of maximum angular rate difference between IMU instances in (rad/s). 7 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/ServorailStatus.msg: -------------------------------------------------------------------------------- 1 | float32 voltage_v # Servo rail voltage in volts 2 | float32 rssi_v # RSSI pin voltage in volts 3 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SubsystemInfo.msg: -------------------------------------------------------------------------------- 1 | uint64 SUBSYSTEM_TYPE_GYRO = 1 2 | uint64 SUBSYSTEM_TYPE_ACC = 2 3 | uint64 SUBSYSTEM_TYPE_MAG = 4 4 | uint64 SUBSYSTEM_TYPE_ABSPRESSURE = 8 5 | uint64 SUBSYSTEM_TYPE_DIFFPRESSURE = 16 6 | uint64 SUBSYSTEM_TYPE_GPS = 32 7 | uint64 SUBSYSTEM_TYPE_OPTICALFLOW = 64 8 | uint64 SUBSYSTEM_TYPE_CVPOSITION = 128 9 | uint64 SUBSYSTEM_TYPE_LASERPOSITION = 256 10 | uint64 SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 512 11 | uint64 SUBSYSTEM_TYPE_ANGULARRATECONTROL = 1024 12 | uint64 SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 2048 13 | uint64 SUBSYSTEM_TYPE_YAWPOSITION = 4096 14 | uint64 SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384 15 | uint64 SUBSYSTEM_TYPE_POSITIONCONTROL = 32768 16 | uint64 SUBSYSTEM_TYPE_MOTORCONTROL = 65536 17 | uint64 SUBSYSTEM_TYPE_RANGEFINDER = 131072 18 | 19 | bool present 20 | bool enabled 21 | bool ok 22 | uint64 subsystem_type 23 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/SystemPower.msg: -------------------------------------------------------------------------------- 1 | float32 voltage5V_v # peripheral 5V rail voltage 2 | uint8 usb_connected # USB is connected when 1 3 | uint8 brick_valid # brick power is good when 1 4 | uint8 servo_valid # servo power is good when 1 5 | uint8 periph_5V_OC # peripheral overcurrent when 1 6 | uint8 hipower_5V_OC # hi power peripheral overcurrent when 1 7 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/TecsStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 TECS_MODE_NORMAL = 0 2 | uint8 TECS_MODE_UNDERSPEED = 1 3 | uint8 TECS_MODE_TAKEOFF = 2 4 | uint8 TECS_MODE_LAND = 3 5 | uint8 TECS_MODE_LAND_THROTTLELIM = 4 6 | uint8 TECS_MODE_BAD_DESCENT = 5 7 | uint8 TECS_MODE_CLIMBOUT = 6 8 | 9 | 10 | float32 altitudeSp 11 | float32 altitude_filtered 12 | float32 flightPathAngleSp 13 | float32 flightPathAngle 14 | float32 flightPathAngleFiltered 15 | float32 airspeedSp 16 | float32 airspeed_filtered 17 | float32 airspeedDerivativeSp 18 | float32 airspeedDerivative 19 | 20 | float32 totalEnergyError 21 | float32 energyDistributionError 22 | float32 totalEnergyRateError 23 | float32 energyDistributionRateError 24 | 25 | float32 throttle_integ 26 | float32 pitch_integ 27 | 28 | uint8 mode 29 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/TelemetryStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0 2 | uint8 TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO = 1 3 | uint8 TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET = 2 4 | uint8 TELEMETRY_STATUS_RADIO_TYPE_WIRE = 3 5 | uint8 TELEMETRY_STATUS_RADIO_TYPE_USB = 4 6 | uint8 TELEMETRY_STATUS_RADIO_TYPE_IRIDIUM = 5 7 | 8 | uint64 heartbeat_time # Time of last received heartbeat from remote system 9 | uint64 telem_time # Time of last received telemetry status packet, 0 for none 10 | uint8 type # type of the radio hardware 11 | uint8 rssi # local signal strength 12 | uint8 remote_rssi # remote signal strength 13 | uint16 rxerrors # receive errors 14 | uint16 fixed # count of error corrected packets 15 | uint8 noise # background noise level 16 | uint8 remote_noise # remote background noise level 17 | uint8 txbuf # how full the tx buffer is as a percentage 18 | uint8 system_id # system id of the remote system 19 | uint8 component_id # component id of the remote system 20 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/TestMotor.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_MOTOR_OUTPUTS = 8 2 | 3 | uint32 motor_number # number of motor to spin 4 | float32 value # output power, range [0..1] 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/TimeOffset.msg: -------------------------------------------------------------------------------- 1 | uint64 offset_ns # time offset between companion system and PX4, in nanoseconds 2 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/TransponderReport.msg: -------------------------------------------------------------------------------- 1 | uint32 ICAO_address # ICAO address 2 | float64 lat # Latitude, expressed as degrees 3 | float64 lon # Longitude, expressed as degrees 4 | uint8 altitude_type # Type from ADSB_ALTITUDE_TYPE enum 5 | float32 altitude # Altitude(ASL) in meters 6 | float32 heading # Course over ground in radians 7 | float32 hor_velocity # The horizontal velocity in m/s 8 | float32 ver_velocity # The vertical velocity in m/s, positive is up 9 | char[9] callsign # The callsign, 8+null 10 | uint8 emitter_type # Type from ADSB_EMITTER_TYPE enum 11 | uint8 tslc # Time since last communication in seconds 12 | uint16 flags # Flags to indicate various statuses including valid data fields 13 | uint16 squawk # Squawk code 14 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/UavcanParameterRequest.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge request type 2 | uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET 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 # -1 if the param_id field should be used as identifier 6 | uint8 param_type # MAVLink parameter type 7 | int64 int_value # current value if param_type is int-like 8 | float32 real_value # current value if param_type is float-like 9 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/UavcanParameterValue.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge response type 2 | uint8 node_id # UAVCAN node ID mapped from MAVLink component ID 3 | char[17] param_id # MAVLink/UAVCAN parameter name 4 | int16 param_index # parameter index, if known 5 | uint16 param_count # number of parameters exposed by the node 6 | uint8 param_type # MAVLink parameter type 7 | int64 int_value # current value if param_type is int-like 8 | float32 real_value # current value if param_type is float-like 9 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/UlogStream.msg: -------------------------------------------------------------------------------- 1 | # Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA 2 | # mavlink message 3 | 4 | # flags bitmasks 5 | uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked. 6 | # Acked messages are published synchronous: a 7 | # publisher waits for an ack before sending the 8 | # next message 9 | 10 | uint8 length # length of data 11 | uint8 first_message_offset # offset into data where first message starts. This 12 | # can be used for recovery, when a previous message got lost 13 | uint16 sequence # allows determine drops 14 | uint8 flags # see FLAGS_* 15 | uint8[249] data # ulog data 16 | 17 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/UlogStreamAck.msg: -------------------------------------------------------------------------------- 1 | # Ack a previously sent ulog_stream message that had 2 | # the NEED_ACK flag set 3 | 4 | int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms] 5 | int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms 6 | 7 | uint16 sequence 8 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleAttitude.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use 2 | float32 rollspeed # Angular velocity about body north axis (x) in rad/s 3 | float32 pitchspeed # Angular velocity about body east axis (y) in rad/s 4 | float32 yawspeed # Angular velocity about body down axis (z) in rad/s 5 | float32[4] q # Quaternion (NED) 6 | 7 | # TOPICS vehicle_attitude vehicle_attitude_groundtruth 8 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | # For quaternion-based attitude control 19 | float32[4] q_d # Desired quaternion for quaternion control 20 | bool q_d_valid # Set to true if quaternion vector is valid 21 | 22 | float32 thrust # Thrust in Newton the power system should generate 23 | 24 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 25 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 26 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 27 | 28 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 29 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 30 | 31 | bool apply_flaps 32 | 33 | float32 landing_gear 34 | 35 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 36 | # TOPICS vehicle_attitude_setpoint 37 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleCommandAck.msg: -------------------------------------------------------------------------------- 1 | uint8 VEHICLE_RESULT_ACCEPTED = 0 2 | uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1 3 | uint8 VEHICLE_RESULT_DENIED = 2 4 | uint8 VEHICLE_RESULT_UNSUPPORTED = 3 5 | uint8 VEHICLE_RESULT_FAILED = 4 6 | 7 | uint32 ORB_QUEUE_LENGTH = 3 8 | 9 | uint16 command 10 | uint8 result 11 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleControlMode.msg: -------------------------------------------------------------------------------- 1 | 2 | # is set whenever the writing thread stores new data 3 | 4 | bool flag_armed 5 | 6 | bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing 7 | 8 | # XXX needs yet to be set by state machine helper 9 | bool flag_system_hil_enabled 10 | 11 | bool flag_control_manual_enabled # true if manual input is mixed in 12 | bool flag_control_auto_enabled # true if onboard autopilot should act 13 | bool flag_control_offboard_enabled # true if offboard control should be used 14 | bool flag_control_rates_enabled # true if rates are stabilized 15 | bool flag_control_attitude_enabled # true if attitude stabilization is mixed in 16 | bool flag_control_rattitude_enabled # true if rate/attitude stabilization is enabled 17 | bool flag_control_force_enabled # true if force control is mixed in 18 | bool flag_control_acceleration_enabled # true if acceleration is controlled 19 | bool flag_control_velocity_enabled # true if horizontal velocity (implies direction) is controlled 20 | bool flag_control_position_enabled # true if position is controlled 21 | bool flag_control_altitude_enabled # true if altitude is controlled 22 | bool flag_control_climb_rate_enabled # true if climb rate is controlled 23 | bool flag_control_termination_enabled # true if flighttermination is enabled 24 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleForceSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Definition of force (NED) setpoint uORB topic. Typically this can be used 2 | # by a position control app together with an attitude control app. 3 | 4 | 5 | float32 x # in N NED 6 | float32 y # in N NED 7 | float32 z # in N NED 8 | float32 yaw # right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw) 9 | -------------------------------------------------------------------------------- /px4_msgs_ros2/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 | uint64 time_utc_usec # GPS UTC timestamp, (microseconds) 8 | float64 lat # Latitude, (degrees) 9 | float64 lon # Longitude, (degrees) 10 | float32 alt # Altitude AMSL, (meters) 11 | float64[2] delta_lat_lon # Reset delta for horizontal position coordinates 12 | float32 delta_alt # Reset delta for altitude 13 | uint8 lat_lon_reset_counter # Counter for reset events on horizontal position coordinates 14 | uint8 alt_reset_counter # Counter for reset events on altitude 15 | float32 vel_n # North velocity in NED earth-fixed frame, (metres/sec) 16 | float32 vel_e # East velocity in NED earth-fixed frame, (metres/sec) 17 | float32 vel_d # Down velocity in NED earth-fixed frame, (metres/sec) 18 | float32 yaw # Euler yaw angle relative to NED earth-fixed frame, -PI..+PI, (radians) 19 | float32 eph # Standard deviation of horizontal position error, (metres) 20 | float32 epv # Standard deviation of vertical position error, (metres) 21 | float32 terrain_alt # Terrain altitude WGS84, (metres) 22 | bool terrain_alt_valid # Terrain altitude estimate is valid 23 | bool dead_reckoning # True if this position is estimated through dead-reckoning 24 | float32 pressure_alt # Pressure altitude AMSL, (metres) 25 | 26 | # TOPICS vehicle_global_position vehicle_global_position_groundtruth 27 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleGlobalVelocitySetpoint.msg: -------------------------------------------------------------------------------- 1 | # Velocity setpoint in NED frame 2 | float32 vx # in m/s NED 3 | float32 vy # in m/s NED 4 | float32 vz # in m/s NED 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleGpsPosition.msg: -------------------------------------------------------------------------------- 1 | # GPS position in WGS84 coordinates. 2 | # the auto-generated field 'timestamp' is for the position & velocity (microseconds) 3 | int32 lat # Latitude in 1E-7 degrees 4 | int32 lon # Longitude in 1E-7 degrees 5 | int32 alt # Altitude in 1E-3 meters above MSL, (millimetres) 6 | int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres) 7 | 8 | float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec) 9 | float32 c_variance_rad # GPS course accuracy estimate, (radians) 10 | uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 11 | 12 | float32 eph # GPS horizontal position accuracy (metres) 13 | float32 epv # GPS vertical position accuracy (metres) 14 | 15 | float32 hdop # Horizontal dilution of precision 16 | float32 vdop # Vertical dilution of precision 17 | 18 | int32 noise_per_ms # GPS noise per millisecond 19 | int32 jamming_indicator # indicates jamming is occurring 20 | 21 | float32 vel_m_s # GPS ground speed, (metres/sec) 22 | float32 vel_n_m_s # GPS North velocity, (metres/sec) 23 | float32 vel_e_m_s # GPS East velocity, (metres/sec) 24 | float32 vel_d_m_s # GPS Down velocity, (metres/sec) 25 | float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians) 26 | bool vel_ned_valid # True if NED velocity is valid 27 | 28 | int32 timestamp_time_relative # timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds) 29 | 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 30 | 31 | uint8 satellites_used # Number of satellites used 32 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleLandDetected.msg: -------------------------------------------------------------------------------- 1 | bool landed # true if vehicle is currently landed on the ground 2 | bool freefall # true if vehicle is currently in free-fall 3 | bool ground_contact # true if vehicle has ground contact but is not landed 4 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleLocalPositionSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Local position setpoint in NED frame 2 | 3 | float32 x # in meters NED 4 | float32 y # in meters NED 5 | float32 z # in meters NED 6 | float32 yaw # in radians NED -PI..+PI 7 | float32 vx # in meters/sec 8 | float32 vy # in meters/sec 9 | float32 vz # in meters/sec 10 | float32 acc_x # in meters/(sec*sec) 11 | float32 acc_y # in meters/(sec*sec) 12 | float32 acc_z # in meters/(sec*sec) 13 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VehicleRoi.msg: -------------------------------------------------------------------------------- 1 | # Vehicle Region Of Interest (ROI) 2 | 3 | uint8 VEHICLE_ROI_NONE = 0 # No region of interest | 4 | uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | 5 | uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | 6 | uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | 7 | uint8 VEHICLE_ROI_TARGET = 4 # Point toward target 8 | uint8 VEHICLE_ROI_ENUM_END = 5 9 | 10 | uint8 mode # ROI mode (see above) 11 | uint32 mission_seq # mission sequence to point to 12 | uint32 target_seq # target sequence to point to 13 | float64 lat # Latitude to point to 14 | float64 lon # Longitude to point to 15 | float32 alt # Altitude to point to 16 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VisionPositionEstimate.msg: -------------------------------------------------------------------------------- 1 | uint32 id # ID of the estimator, commonly the component ID of the incoming message 2 | 3 | uint64 timestamp_received # timestamp when the estimate was received 4 | 5 | float32 x # X position in meters in NED earth-fixed frame 6 | float32 y # Y position in meters in NED earth-fixed frame 7 | float32 z # Z position in meters in NED earth-fixed frame (negative altitude) 8 | 9 | float32 vx # X velocity in meters per second in NED earth-fixed frame 10 | float32 vy # Y velocity in meters per second in NED earth-fixed frame 11 | float32 vz # Z velocity in meters per second in NED earth-fixed frame 12 | 13 | float32[4] q # Estimated attitude as quaternion 14 | 15 | float32 pos_err # position error 1-std for each axis (metres) 16 | float32 ang_err # angular error 1-std for each axis (rad) 17 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/VtolVehicleStatus.msg: -------------------------------------------------------------------------------- 1 | # VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE 2 | uint8 VEHICLE_VTOL_STATE_UNDEFINED = 0 3 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_FW = 1 4 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2 5 | uint8 VEHICLE_VTOL_STATE_MC = 3 6 | uint8 VEHICLE_VTOL_STATE_FW = 4 7 | uint8 VEHICLE_VTOL_STATE_EXTERNAL = 5 8 | 9 | bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode 10 | bool vtol_in_trans_mode 11 | bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW 12 | bool vtol_transition_failsafe # vtol in transition failsafe mode 13 | bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode 14 | float32 airspeed_tot # Estimated airspeed over control surfaces 15 | -------------------------------------------------------------------------------- /px4_msgs_ros2/msg/WindEstimate.msg: -------------------------------------------------------------------------------- 1 | float32 windspeed_north # Wind component in north / X direction 2 | float32 windspeed_east # Wind component in east / Y direction 3 | float32 covariance_north # Uncertainty - set to zero (no uncertainty) if not estimated 4 | float32 covariance_east # Uncertainty - set to zero (no uncertainty) if not estimated 5 | -------------------------------------------------------------------------------- /px4_msgs_ros2/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | px4_msgs 5 | 0.0.0 6 | Communication demo between PX4 and ROS2 7 | Javier Isabel 8 | Apache License 2.0 9 | 10 | ament_cmake 11 | 12 | builtin_interfaces 13 | rosidl_default_generators 14 | builtin_interfaces 15 | rosidl_default_runtime 16 | 17 | 18 | ament_cmake 19 | 20 | 21 | -------------------------------------------------------------------------------- /px4_msgs_ros2/scripts/copy_and_rename.py: -------------------------------------------------------------------------------- 1 | import os 2 | import sys 3 | 4 | from shutil import copyfile 5 | 6 | print("Number of arguments:", len(sys.argv), "arguments.") 7 | print("Argument List:", str(sys.argv)) 8 | 9 | input_dir = sys.argv[1] 10 | output_dir = sys.argv[2] 11 | 12 | for filename in os.listdir(input_dir): 13 | if ".msg" in filename: 14 | input_file = input_dir + filename 15 | output_file = output_dir + filename.partition(".")[0].title().replace('_','') + ".msg" 16 | copyfile(input_file, output_file) 17 | print "Created " + output_file 18 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/doc/bridge-ROS2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/eProsima/px4_to_ros/7329dda1d1614c27da982f32a4d8fc7afd03b957/px4_to_ros2_PoC/doc/bridge-ROS2.png -------------------------------------------------------------------------------- /px4_to_ros2_PoC/latency/AMENT_IGNORE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/eProsima/px4_to_ros/7329dda1d1614c27da982f32a4d8fc7afd03b957/px4_to_ros2_PoC/latency/AMENT_IGNORE -------------------------------------------------------------------------------- /px4_to_ros2_PoC/latency/micrortps_agent/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.12) 2 | project(micrortps_receiver) 3 | 4 | # Find requirements 5 | find_package(fastrtps REQUIRED) 6 | find_package(fastcdr REQUIRED) 7 | 8 | # Set C++11 9 | include(CheckCXXCompilerFlag) 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG OR 11 | CMAKE_CXX_COMPILER_ID MATCHES "Clang") 12 | check_cxx_compiler_flag(--std=c++11 SUPPORTS_CXX11) 13 | if(SUPPORTS_CXX11) 14 | add_compile_options(--std=c++11) 15 | else() 16 | message(FATAL_ERROR "Compiler doesn't support C++11") 17 | endif() 18 | endif() 19 | 20 | file(GLOB MICRORTPS_AGENT_SOURCES *.cxx) 21 | add_executable(micrortps_agent ${MICRORTPS_AGENT_SOURCES}) 22 | target_link_libraries(micrortps_agent fastrtps fastcdr) -------------------------------------------------------------------------------- /px4_to_ros2_PoC/latency/micrortps_agent/UART_node.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | 20 | 21 | class UART_node 22 | { 23 | public: 24 | UART_node(); 25 | virtual ~UART_node(); 26 | 27 | uint8_t init_uart(const char * uart_name); 28 | uint8_t close_uart(); 29 | int16_t readFromUART(char* topic_ID, char out_buffer[], char rx_buffer[], uint32_t &rx_buff_pos, uint32_t max_size); 30 | int16_t writeToUART(const char topic_ID, char buffer[], uint32_t length); 31 | 32 | protected: 33 | uint16_t crc16_byte(uint16_t crc, const uint8_t data); 34 | uint16_t crc16(uint8_t const *buffer, size_t len); 35 | 36 | protected: 37 | 38 | int m_uart_filestream; 39 | }; 40 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/latency/micrortps_agent/sensor_combined_PubSubTypes.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | /*! 16 | * @file sensor_combined_PubSubTypes.h 17 | * This header file contains the declaration of the serialization functions. 18 | * 19 | * This file was generated by the tool fastcdrgen. 20 | */ 21 | 22 | 23 | #ifndef _SENSOR_COMBINED__PUBSUBTYPES_H_ 24 | #define _SENSOR_COMBINED__PUBSUBTYPES_H_ 25 | 26 | #include 27 | 28 | using namespace eprosima::fastrtps; 29 | 30 | #include "sensor_combined_.h" 31 | 32 | /*! 33 | * @brief This class represents the TopicDataType of the type sensor_combined_ defined by the user in the IDL file. 34 | * @ingroup SENSOR_COMBINED_ 35 | */ 36 | class sensor_combined_PubSubType : public TopicDataType { 37 | public: 38 | typedef sensor_combined_ type; 39 | 40 | sensor_combined_PubSubType(); 41 | virtual ~sensor_combined_PubSubType(); 42 | bool serialize(void *data, SerializedPayload_t *payload); 43 | bool deserialize(SerializedPayload_t *payload, void *data); 44 | std::function getSerializedSizeProvider(void* data); 45 | bool getKey(void *data, InstanceHandle_t *ihandle); 46 | void* createData(); 47 | void deleteData(void * data); 48 | MD5 m_md5; 49 | unsigned char* m_keyBuffer; 50 | }; 51 | 52 | #endif // _sensor_combined__PUBSUBTYPE_H_ 53 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/latency/micrortps_agent/sensor_combined_Publisher.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | /*! 16 | * @file sensor_combined_Publisher.h 17 | * This header file contains the declaration of the publisher functions. 18 | * 19 | * This file was generated by the tool fastcdrgen. 20 | */ 21 | 22 | 23 | #ifndef _sensor_combined__PUBLISHER_H_ 24 | #define _sensor_combined__PUBLISHER_H_ 25 | 26 | #include 27 | #include 28 | 29 | #include "sensor_combined_PubSubTypes.h" 30 | 31 | using namespace eprosima::fastrtps; 32 | 33 | class sensor_combined_Publisher 34 | { 35 | public: 36 | sensor_combined_Publisher(); 37 | virtual ~sensor_combined_Publisher(); 38 | bool init(); 39 | void run(); 40 | void publish(sensor_combined_* st); 41 | private: 42 | Participant *mp_participant; 43 | Publisher *mp_publisher; 44 | 45 | class PubListener : public PublisherListener 46 | { 47 | public: 48 | PubListener() : n_matched(0){}; 49 | ~PubListener(){}; 50 | void onPublicationMatched(Publisher* pub,MatchingInfo& info); 51 | int n_matched; 52 | } m_listener; 53 | sensor_combined_PubSubType myType; 54 | }; 55 | 56 | #endif // _sensor_combined__PUBLISHER_H_ -------------------------------------------------------------------------------- /px4_to_ros2_PoC/latency/micrortps_client/UART_node.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | 20 | 21 | class UART_node 22 | { 23 | public: 24 | UART_node(); 25 | virtual ~UART_node(); 26 | 27 | uint8_t init_uart(const char * uart_name); 28 | uint8_t close_uart(); 29 | int16_t readFromUART(char* topic_ID, char out_buffer[], char rx_buffer[], uint32_t &rx_buff_pos, uint32_t max_size); 30 | int16_t writeToUART(const char topic_ID, char buffer[], uint32_t length); 31 | 32 | protected: 33 | uint16_t crc16_byte(uint16_t crc, const uint8_t data); 34 | uint16_t crc16(uint8_t const *buffer, size_t len); 35 | 36 | protected: 37 | 38 | int m_uart_filestream; 39 | }; 40 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_agent/AMENT_IGNORE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/eProsima/px4_to_ros/7329dda1d1614c27da982f32a4d8fc7afd03b957/px4_to_ros2_PoC/micrortps_agent/AMENT_IGNORE -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_agent/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.12) 2 | project(micrortps_receiver) 3 | 4 | # Find requirements 5 | find_package(fastrtps REQUIRED) 6 | find_package(fastcdr REQUIRED) 7 | 8 | # Set C++11 9 | include(CheckCXXCompilerFlag) 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG OR 11 | CMAKE_CXX_COMPILER_ID MATCHES "Clang") 12 | check_cxx_compiler_flag(--std=c++11 SUPPORTS_CXX11) 13 | if(SUPPORTS_CXX11) 14 | add_compile_options(--std=c++11) 15 | else() 16 | message(FATAL_ERROR "Compiler doesn't support C++11") 17 | endif() 18 | endif() 19 | 20 | file(GLOB MICRORTPS_AGENT_SOURCES *.cxx) 21 | add_executable(micrortps_agent ${MICRORTPS_AGENT_SOURCES}) 22 | target_link_libraries(micrortps_agent fastrtps fastcdr) -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_agent/UART_node.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | 20 | 21 | class UART_node 22 | { 23 | public: 24 | UART_node(); 25 | virtual ~UART_node(); 26 | 27 | uint8_t init_uart(const char * uart_name); 28 | uint8_t close_uart(); 29 | int16_t readFromUART(char* topic_ID, char out_buffer[], char rx_buffer[], uint32_t &rx_buff_pos, uint32_t max_size); 30 | int16_t writeToUART(const char topic_ID, char buffer[], uint32_t length); 31 | 32 | protected: 33 | uint16_t crc16_byte(uint16_t crc, const uint8_t data); 34 | uint16_t crc16(uint8_t const *buffer, size_t len); 35 | 36 | protected: 37 | 38 | int m_uart_filestream; 39 | }; 40 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_agent/sensor_combined_PubSubTypes.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | /*! 16 | * @file sensor_combined_PubSubTypes.h 17 | * This header file contains the declaration of the serialization functions. 18 | * 19 | * This file was generated by the tool fastcdrgen. 20 | */ 21 | 22 | 23 | #ifndef _SENSOR_COMBINED__PUBSUBTYPES_H_ 24 | #define _SENSOR_COMBINED__PUBSUBTYPES_H_ 25 | 26 | #include 27 | 28 | using namespace eprosima::fastrtps; 29 | 30 | #include "sensor_combined_.h" 31 | 32 | /*! 33 | * @brief This class represents the TopicDataType of the type sensor_combined_ defined by the user in the IDL file. 34 | * @ingroup SENSOR_COMBINED_ 35 | */ 36 | class sensor_combined_PubSubType : public TopicDataType { 37 | public: 38 | typedef sensor_combined_ type; 39 | 40 | sensor_combined_PubSubType(); 41 | virtual ~sensor_combined_PubSubType(); 42 | bool serialize(void *data, SerializedPayload_t *payload); 43 | bool deserialize(SerializedPayload_t *payload, void *data); 44 | std::function getSerializedSizeProvider(void* data); 45 | bool getKey(void *data, InstanceHandle_t *ihandle); 46 | void* createData(); 47 | void deleteData(void * data); 48 | MD5 m_md5; 49 | unsigned char* m_keyBuffer; 50 | }; 51 | 52 | #endif // _sensor_combined__PUBSUBTYPE_H_ 53 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_agent/sensor_combined_Publisher.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | /*! 16 | * @file sensor_combined_Publisher.h 17 | * This header file contains the declaration of the publisher functions. 18 | * 19 | * This file was generated by the tool fastcdrgen. 20 | */ 21 | 22 | 23 | #ifndef _sensor_combined__PUBLISHER_H_ 24 | #define _sensor_combined__PUBLISHER_H_ 25 | 26 | #include 27 | #include 28 | 29 | #include "sensor_combined_PubSubTypes.h" 30 | 31 | using namespace eprosima::fastrtps; 32 | 33 | class sensor_combined_Publisher 34 | { 35 | public: 36 | sensor_combined_Publisher(); 37 | virtual ~sensor_combined_Publisher(); 38 | bool init(); 39 | void run(); 40 | void publish(sensor_combined_* st); 41 | private: 42 | Participant *mp_participant; 43 | Publisher *mp_publisher; 44 | 45 | class PubListener : public PublisherListener 46 | { 47 | public: 48 | PubListener() : n_matched(0){}; 49 | ~PubListener(){}; 50 | void onPublicationMatched(Publisher* pub,MatchingInfo& info); 51 | int n_matched; 52 | } m_listener; 53 | sensor_combined_PubSubType myType; 54 | }; 55 | 56 | #endif // _sensor_combined__PUBLISHER_H_ -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_client/AMENT_IGNORE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/eProsima/px4_to_ros/7329dda1d1614c27da982f32a4d8fc7afd03b957/px4_to_ros2_PoC/micrortps_client/AMENT_IGNORE -------------------------------------------------------------------------------- /px4_to_ros2_PoC/micrortps_client/UART_node.h: -------------------------------------------------------------------------------- 1 | // Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | 20 | 21 | class UART_node 22 | { 23 | public: 24 | UART_node(); 25 | virtual ~UART_node(); 26 | 27 | uint8_t init_uart(const char * uart_name); 28 | uint8_t close_uart(); 29 | int16_t readFromUART(char* topic_ID, char out_buffer[], char rx_buffer[], uint32_t &rx_buff_pos, uint32_t max_size); 30 | int16_t writeToUART(const char topic_ID, char buffer[], uint32_t length); 31 | 32 | protected: 33 | uint16_t crc16_byte(uint16_t crc, const uint8_t data); 34 | uint16_t crc16(uint8_t const *buffer, size_t len); 35 | 36 | protected: 37 | 38 | int m_uart_filestream; 39 | }; 40 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ActuatorArmed.msg: -------------------------------------------------------------------------------- 1 | 2 | bool armed # Set to true if system is armed 3 | bool prearmed # Set to true if the actuator safety is disabled but motors are not armed 4 | bool ready_to_arm # Set to true if system is ready to be armed 5 | bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL) 6 | bool manual_lockdown # Set to true if manual throttle kill switch is engaged 7 | bool force_failsafe # Set to true if the actuators are forced to the failsafe position 8 | bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics 9 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ActuatorControls.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATOR_CONTROLS = 8 2 | uint8 NUM_ACTUATOR_CONTROL_GROUPS = 4 3 | uint8 INDEX_ROLL = 0 4 | uint8 INDEX_PITCH = 1 5 | uint8 INDEX_YAW = 2 6 | uint8 INDEX_THROTTLE = 3 7 | uint8 INDEX_FLAPS = 4 8 | uint8 INDEX_SPOILERS = 5 9 | uint8 INDEX_AIRBRAKES = 6 10 | uint8 INDEX_LANDING_GEAR = 7 11 | uint8 GROUP_INDEX_ATTITUDE = 0 12 | uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1 13 | uint64 timestamp_sample # the timestamp the data this control response is based on was sampled 14 | float32[8] control 15 | 16 | # TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3 17 | # TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc 18 | 19 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ActuatorDirect.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATORS_DIRECT = 16 2 | uint32 nvalues # number of valid values 3 | float32[16] values # actuator values, from -1 to 1 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ActuatorOutputs.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_ACTUATOR_OUTPUTS = 16 2 | uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking 3 | uint32 noutputs # valid outputs 4 | float32[16] output # output data, in natural output units 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/AdcReport.msg: -------------------------------------------------------------------------------- 1 | int16[8] channel_id # ADC channel IDs, negative for non-existent 2 | float32[8] channel_value # ADC channel value in volt, valid if channel ID is positive 3 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/Airspeed.msg: -------------------------------------------------------------------------------- 1 | float32 indicated_airspeed_m_s # indicated airspeed in meters per second, -1 if unknown 2 | float32 true_airspeed_m_s # true filtered airspeed in meters per second, -1 if unknown 3 | float32 true_airspeed_unfiltered_m_s # true airspeed in meters per second, -1 if unknown 4 | float32 air_temperature_celsius # air temperature in degrees celsius, -1000 if unknown 5 | float32 confidence # confidence value from 0 to 1 for this sensor 6 | float32 differential_pressure_filtered_pa # filtered differential pressure, can be negative 7 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/AttPosMocap.msg: -------------------------------------------------------------------------------- 1 | uint32 id # ID of the estimator, commonly the component ID of the incoming message 2 | 3 | uint64 timestamp_received # timestamp when the estimate was received 4 | 5 | float32[4] q # Estimated attitude as quaternion 6 | 7 | float32 x # X position in meters in NED earth-fixed frame 8 | float32 y # Y position in meters in NED earth-fixed frame 9 | float32 z # Z position in meters in NED earth-fixed frame (negative altitude) 10 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/BatteryStatus.msg: -------------------------------------------------------------------------------- 1 | float32 voltage_v # Battery voltage in volts, 0 if unknown 2 | float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown 3 | float32 current_a # Battery current in amperes, -1 if unknown 4 | float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown 5 | float32 discharged_mah # Discharged amount in mAh, -1 if unknown 6 | float32 remaining # From 1 to 0, -1 if unknown 7 | float32 scale # Power scaling factor, >= 1, or -1 if unknown 8 | int32 cell_count # Number of cells 9 | bool connected # Wether or not a battery is connected 10 | #bool is_powering_off # Power off event imminent indication, false if unknown 11 | 12 | 13 | uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active 14 | uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage 15 | uint8 BATTERY_WARNING_CRITICAL = 2 # alerting of critical voltage 16 | 17 | uint8 warning # current battery warning 18 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/CameraTrigger.msg: -------------------------------------------------------------------------------- 1 | 2 | uint32 seq # Image sequence 3 | 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/CollisionReport.msg: -------------------------------------------------------------------------------- 1 | uint8 src 2 | uint32 id 3 | uint8 action 4 | uint8 threat_level 5 | float32 time_to_minimum_delta 6 | float32 altitude_minimum_delta 7 | float32 horizontal_minimum_delta 8 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/CommanderState.msg: -------------------------------------------------------------------------------- 1 | # Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link. 2 | uint8 MAIN_STATE_MANUAL = 0 3 | uint8 MAIN_STATE_ALTCTL = 1 4 | uint8 MAIN_STATE_POSCTL = 2 5 | uint8 MAIN_STATE_AUTO_MISSION = 3 6 | uint8 MAIN_STATE_AUTO_LOITER = 4 7 | uint8 MAIN_STATE_AUTO_RTL = 5 8 | uint8 MAIN_STATE_ACRO = 6 9 | uint8 MAIN_STATE_OFFBOARD = 7 10 | uint8 MAIN_STATE_STAB = 8 11 | uint8 MAIN_STATE_RATTITUDE = 9 12 | uint8 MAIN_STATE_AUTO_TAKEOFF = 10 13 | uint8 MAIN_STATE_AUTO_LAND = 11 14 | uint8 MAIN_STATE_AUTO_FOLLOW_TARGET = 12 15 | uint8 MAIN_STATE_MAX = 13 16 | 17 | 18 | uint8 main_state # main state machine 19 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ControlState.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message CONTROL_SYSTEM_STATE, but for onboard use */ 2 | uint8 AIRSPD_MODE_MEAS = 0 # airspeed is measured airspeed from sensor 3 | uint8 AIRSPD_MODE_EST = 1 # airspeed is estimated by body velocity 4 | uint8 AIRSPD_MODE_DISABLED = 2 # airspeed is disabled 5 | 6 | float32 x_acc # X acceleration in body frame 7 | float32 y_acc # Y acceleration in body frame 8 | float32 z_acc # Z acceleration in body frame 9 | float32 x_vel # X velocity in body frame 10 | float32 y_vel # Y velocity in body frame 11 | float32 z_vel # Z velocity in body frame 12 | float32 x_pos # X position in local earth frame 13 | float32 y_pos # Y position in local earth frame 14 | float32 z_pos # z position in local earth frame 15 | float32 airspeed # Airspeed, estimated 16 | bool airspeed_valid # False: Non-finite values or non-updating sensor 17 | float32[3] vel_variance # Variance in body velocity estimate 18 | float32[3] pos_variance # Variance in local position estimate 19 | float32[4] q # Attitude Quaternion 20 | float32[4] delta_q_reset # Amount by which quaternion has changed during last reset 21 | uint8 quat_reset_counter # Quaternion reset counter 22 | float32 roll_rate # Roll body angular rate (rad/s, x forward/y right/z down) - corrected for bias 23 | float32 pitch_rate # Pitch body angular rate (rad/s, x forward/y right/z down) - corrected for bias 24 | float32 yaw_rate # Yaw body angular rate (rad/s, x forward/y right/z down) - corrected for bias 25 | float32 horz_acc_mag # low pass filtered magnitude of the horizontal acceleration 26 | float32 roll_rate_bias # Roll body angular rate bias (rad/s, x forward) - subtract from uncorrected gyro data 27 | float32 pitch_rate_bias # Pitch body angular rate bias (rad/s, y right) - subtract from uncorrected gyro data 28 | float32 yaw_rate_bias # Yaw body angular rate bias (rad/s, z down) - subtract from uncorrected gyro data 29 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/Cpuload.msg: -------------------------------------------------------------------------------- 1 | float32 load # processor load from 0 to 1 2 | float32 ram_usage # RAM usage from 0 to 1 3 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/DebugKeyValue.msg: -------------------------------------------------------------------------------- 1 | uint32 timestamp_ms # in milliseconds since system start 2 | int8[10] key # max. 10 characters as key / name 3 | float32 value # the value to send as debug output 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/DifferentialPressure.msg: -------------------------------------------------------------------------------- 1 | uint64 error_count # Number of errors detected by driver 2 | float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative) 3 | float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading 4 | float32 max_differential_pressure_pa # Maximum differential pressure reading 5 | float32 temperature # Temperature provided by sensor, -1000.0f if unknown 6 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/DistanceSensor.msg: -------------------------------------------------------------------------------- 1 | # DISTANCE_SENSOR message data 2 | 3 | 4 | float32 min_distance # Minimum distance the sensor can measure (in m) 5 | float32 max_distance # Maximum distance the sensor can measure (in m) 6 | float32 current_distance # Current distance reading (in m) 7 | float32 covariance # Measurement covariance (in m), 0 for unknown / invalid readings 8 | 9 | uint8 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 | uint8 id # Onboard ID of the sensor 16 | 17 | uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum 18 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/Ekf2Innovations.msg: -------------------------------------------------------------------------------- 1 | float32[6] vel_pos_innov # velocity and position innovations 2 | float32[3] mag_innov # earth magnetic field innovations 3 | float32 heading_innov # heading innovation 4 | float32 airspeed_innov # airspeed innovation 5 | float32 beta_innov # synthetic sideslip innovation 6 | float32[2] flow_innov # flow innovation 7 | float32 hagl_innov # innovation from the terrain estimator for the height above ground level measurement (m) 8 | float32[6] vel_pos_innov_var # velocity and position innovation variances 9 | float32[3] mag_innov_var # earth magnetic field innovation variance 10 | float32 heading_innov_var # heading innovation variance 11 | float32 airspeed_innov_var # Airspeed innovation variance 12 | float32 beta_innov_var # synthetic sideslip innovation variance 13 | float32[2] flow_innov_var # flow innovation variance 14 | float32 hagl_innov_var # innovation variance from the terrain estimator for the height above ground level measurement (m^2) 15 | float32[3] output_tracking_error # return a vector containing the output predictor angular, velocity and position tracking error magnitudes (rad), (m/s), (m) 16 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/EscReport.msg: -------------------------------------------------------------------------------- 1 | uint8 esc_vendor # Vendor of current ESC 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 | float32 esc_setpoint # setpoint of current ESC 8 | uint16 esc_setpoint_raw # setpoint of current ESC (Value sent to ESC) 9 | uint16 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver) 10 | uint16 esc_version # Version of current ESC - if supported 11 | uint16 esc_state # State of ESC - depend on Vendor 12 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/EscStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs 2 | 3 | uint8 ESC_VENDOR_GENERIC = 0 # generic ESC 4 | uint8 ESC_VENDOR_MIKROKOPTER = 1 # Mikrokopter 5 | uint8 ESC_VENDOR_GRAUPNER_HOTT = 2 # Graupner HoTT ESC 6 | uint8 ESC_VENDOR_TAP = 3 # TAP ESC 7 | 8 | uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC 9 | uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC 10 | uint8 ESC_CONNECTION_TYPE_ONESHOOT = 2 # One Shoot PPM 11 | uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C 12 | uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus 13 | 14 | uint16 counter # incremented by the writing thread everytime new data is stored 15 | 16 | uint8 esc_count # number of connected ESCs 17 | uint8 esc_connectiontype # how ESCs connected to the system 18 | 19 | esc_report[8] esc 20 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/Fence.msg: -------------------------------------------------------------------------------- 1 | uint8 GEOFENCE_MAX_VERTICES = 16 2 | 3 | uint32 count # number of actual vertices 4 | fence_vertex[16] vertices # geofence positions 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/FenceVertex.msg: -------------------------------------------------------------------------------- 1 | float32 lat # latitude in degrees, worst case float precision gives us 2 meter resolution at the equator 2 | float32 lon # longitude in degrees, worst case float precision gives us 2 meter resolution at the equator 3 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/FilteredBottomFlow.msg: -------------------------------------------------------------------------------- 1 | # Filtered bottom flow in bodyframe. 2 | 3 | float32 sumx # Integrated bodyframe x flow in meters 4 | float32 sumy # Integrated bodyframe y flow in meters 5 | 6 | float32 vx # Flow bodyframe x speed, m/s 7 | float32 vy # Flow bodyframe y Speed, m/s 8 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/FollowTarget.msg: -------------------------------------------------------------------------------- 1 | float64 lat # target position (deg * 1e7) 2 | float64 lon # target position (deg * 1e7) 3 | float32 alt # target position 4 | float32 vy # target vel in y 5 | float32 vx # target vel in x 6 | float32 vz # target vel in z 7 | uint8 est_cap # target reporting capabilities 8 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/FwPosCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | float32 nav_roll 2 | float32 nav_pitch 3 | float32 nav_bearing 4 | 5 | float32 target_bearing 6 | float32 wp_dist 7 | float32 xtrack_error 8 | float32 turn_distance # the optimal distance to a waypoint to switch to the next 9 | 10 | float32 landing_horizontal_slope_displacement 11 | float32 landing_slope_angle_rad 12 | float32 landing_flare_length 13 | bool abort_landing 14 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/FwVirtualAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame 19 | bool R_valid # Set to true if rotation matrix is valid 20 | 21 | # For quaternion-based attitude control 22 | float32[4] q_d # Desired quaternion for quaternion control 23 | bool q_d_valid # Set to true if quaternion vector is valid 24 | float32[4] q_e # Attitude error in quaternion 25 | bool q_e_valid # Set to true if quaternion error vector is valid 26 | 27 | float32 thrust # Thrust in Newton the power system should generate 28 | 29 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 30 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 31 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 32 | 33 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 34 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 35 | 36 | bool apply_flaps 37 | 38 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 39 | # TOPICS fw_virtual_attitude_setpoint 40 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/FwVirtualRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/GeofenceResult.msg: -------------------------------------------------------------------------------- 1 | uint8 GF_ACTION_NONE = 0 # no action on geofence violation 2 | uint8 GF_ACTION_WARN = 1 # critical mavlink message 3 | uint8 GF_ACTION_LOITER = 2 # switch to AUTO|LOITER 4 | uint8 GF_ACTION_RTL = 3 # switch to AUTO|RTL 5 | uint8 GF_ACTION_TERMINATE = 4 # flight termination 6 | 7 | bool geofence_violated # true if the geofence is violated 8 | uint8 geofence_action # action to take when geofence is violated -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/GpsDump.msg: -------------------------------------------------------------------------------- 1 | # This message is used to dump the raw gps communication to the log. 2 | # Set the parameter GPS_DUMP_COMM to 1 to use this. 3 | 4 | uint8 len # length of data, MSB bit set = message to the gps device, 5 | # clear = message from the device 6 | uint8[79] data # data to write to the log 7 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/GpsInjectData.msg: -------------------------------------------------------------------------------- 1 | uint8 len # length of data 2 | uint8 flags # LSB: 1=fragmented 3 | uint8[182] data # data to write to GPS device (RTCM message) 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/HomePosition.msg: -------------------------------------------------------------------------------- 1 | # GPS home position in WGS84 coordinates. 2 | 3 | float64 lat # Latitude in degrees 4 | float64 lon # Longitude in degrees 5 | float32 alt # Altitude in meters (AMSL) 6 | 7 | float32 x # X coordinate in meters 8 | float32 y # Y coordinate in meters 9 | float32 z # Z coordinate in meters 10 | 11 | float32 yaw # Yaw angle in radians 12 | float32 direction_x # Takeoff direction in NED X 13 | float32 direction_y # Takeoff direction in NED Y 14 | float32 direction_z # Takeoff direction in NED Z 15 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/LogMessage.msg: -------------------------------------------------------------------------------- 1 | # A logging message, output with PX4_{WARN,ERR,INFO} 2 | 3 | uint8 severity # log level (same as in the linux kernel, starting with 0) 4 | uint8[127] text 5 | 6 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/LowStack.msg: -------------------------------------------------------------------------------- 1 | uint8 MAX_REPORT_TASK_NAME_LEN = 16 2 | 3 | uint16 stack_free 4 | uint8[16] task_name 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/MavlinkLog.msg: -------------------------------------------------------------------------------- 1 | 2 | uint8[50] text 3 | uint8 severity # log level (same as in the linux kernel, starting with 0) 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/McAttCtrlStatus.msg: -------------------------------------------------------------------------------- 1 | 2 | float32 roll_rate_integ # roll rate inegrator 3 | float32 pitch_rate_integ # pitch rate integrator 4 | float32 yaw_rate_integ # yaw rate integrator 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/McVirtualAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame 19 | bool R_valid # Set to true if rotation matrix is valid 20 | 21 | # For quaternion-based attitude control 22 | float32[4] q_d # Desired quaternion for quaternion control 23 | bool q_d_valid # Set to true if quaternion vector is valid 24 | float32[4] q_e # Attitude error in quaternion 25 | bool q_e_valid # Set to true if quaternion error vector is valid 26 | 27 | float32 thrust # Thrust in Newton the power system should generate 28 | 29 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 30 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 31 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 32 | 33 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 34 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 35 | 36 | bool apply_flaps 37 | 38 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 39 | # TOPICS mc_virtual_attitude_setpoint 40 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/McVirtualRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/Mission.msg: -------------------------------------------------------------------------------- 1 | int32 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1 2 | uint32 count # count of the missions stored in the dataman 3 | int32 current_seq # default -1, start at the one changed latest 4 | 5 | # TOPICS mission offboard_mission onboard_mission 6 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/MissionResult.msg: -------------------------------------------------------------------------------- 1 | uint32 instance_count # Instance count of this mission. Increments monotonically whenever the mission is modified 2 | uint32 seq_reached # Sequence of the mission item which has been reached 3 | uint32 seq_current # Sequence of the current mission item 4 | uint32 seq_total # Total number of mission items 5 | bool valid # true if mission is valid 6 | bool warning # true if mission is valid, but has potentially problematic items leading to safety warnings 7 | bool reached # true if mission has been reached 8 | bool finished # true if mission has been completed 9 | bool stay_in_failsafe # true if the commander should not switch out of the failsafe mode 10 | bool flight_termination # true if the navigator demands a flight termination from the commander app 11 | bool item_do_jump_changed # true if the number of do jumps remaining has changed 12 | uint32 item_changed_index # indicate which item has changed 13 | uint32 item_do_jump_remaining # set to the number of do jumps remaining for that item 14 | bool mission_failure # true if the mission cannot continue or be completed for some reason 15 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/MountOrientation.msg: -------------------------------------------------------------------------------- 1 | float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad 2 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/MultirotorMotorLimits.msg: -------------------------------------------------------------------------------- 1 | uint16 saturation_status # Integer bit mask indicating which axes in the control mixer are saturated 2 | # 0 - True if any motor is saturated at the upper limit 3 | # 1 - True if any motor is saturated at the lower limit 4 | # 2 - True if a positive roll increment will increase motor saturation 5 | # 3 - True if negative roll increment will increase motor saturation 6 | # 4 - True if positive pitch increment will increase motor saturation 7 | # 5 - True if negative pitch increment will increase motor saturation 8 | # 6 - True if positive yaw increment will increase motor saturation 9 | # 7 - True if negative yaw increment will increase motor saturation 10 | # 8 - True if positive thrust increment will increase motor saturation 11 | # 9 - True if negative thrust increment will increase motor saturation 12 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/OffboardControlMode.msg: -------------------------------------------------------------------------------- 1 | # Off-board control mode 2 | 3 | bool ignore_thrust 4 | bool ignore_attitude 5 | bool ignore_bodyrate 6 | bool ignore_position 7 | bool ignore_velocity 8 | bool ignore_acceleration_force 9 | bool ignore_alt_hold 10 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/OpticalFlow.msg: -------------------------------------------------------------------------------- 1 | # Optical flow in XYZ body frame in SI units. 2 | # @see http://en.wikipedia.org/wiki/International_System_of_Units 3 | 4 | uint8 sensor_id # id of the sensor emitting the flow value 5 | float32 pixel_flow_x_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the X body axis 6 | float32 pixel_flow_y_integral # accumulated optical flow in radians where a positive value is produced by a RH rotation about the Y body axis 7 | float32 gyro_x_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the X body axis 8 | float32 gyro_y_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the Y body axis 9 | float32 gyro_z_rate_integral # accumulated gyro value in radians where a positive value is produced by a RH rotation about the Z body axis 10 | float32 ground_distance_m # Altitude / distance to ground in meters 11 | uint32 integration_timespan # accumulation timespan in microseconds 12 | uint32 time_since_last_sonar_update # time since last sonar update in microseconds 13 | uint16 frame_count_since_last_readout # number of accumulated frames in timespan 14 | int16 gyro_temperature # Temperature * 100 in centi-degrees Celsius 15 | uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: maximum quality 16 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/OutputPwm.msg: -------------------------------------------------------------------------------- 1 | uint8 PWM_OUTPUT_MAX_CHANNELS = 16 2 | uint16[16] values 3 | uint32 channel_count 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ParameterUpdate.msg: -------------------------------------------------------------------------------- 1 | bool saved # wether the change has already been saved to disk 2 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/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 | px4/position_setpoint previous 5 | px4/position_setpoint current 6 | px4/position_setpoint next 7 | 8 | uint8 nav_state # report the navigation state 9 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/PwmInput.msg: -------------------------------------------------------------------------------- 1 | 2 | uint64 error_count 3 | uint32 pulse_width # Pulse width, timer counts 4 | uint32 period # Period, timer counts 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/QshellReq.msg: -------------------------------------------------------------------------------- 1 | int32[100] string 2 | uint64 MAX_STRLEN = 100 3 | uint64 strlen 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/RcChannels.msg: -------------------------------------------------------------------------------- 1 | int32 RC_CHANNELS_FUNCTION_MAX=21 2 | uint8 RC_CHANNELS_FUNCTION_THROTTLE=0 3 | uint8 RC_CHANNELS_FUNCTION_ROLL=1 4 | uint8 RC_CHANNELS_FUNCTION_PITCH=2 5 | uint8 RC_CHANNELS_FUNCTION_YAW=3 6 | uint8 RC_CHANNELS_FUNCTION_MODE=4 7 | uint8 RC_CHANNELS_FUNCTION_RETURN=5 8 | uint8 RC_CHANNELS_FUNCTION_POSCTL=6 9 | uint8 RC_CHANNELS_FUNCTION_LOITER=7 10 | uint8 RC_CHANNELS_FUNCTION_OFFBOARD=8 11 | uint8 RC_CHANNELS_FUNCTION_ACRO=9 12 | uint8 RC_CHANNELS_FUNCTION_FLAPS=10 13 | uint8 RC_CHANNELS_FUNCTION_AUX_1=11 14 | uint8 RC_CHANNELS_FUNCTION_AUX_2=12 15 | uint8 RC_CHANNELS_FUNCTION_AUX_3=13 16 | uint8 RC_CHANNELS_FUNCTION_AUX_4=14 17 | uint8 RC_CHANNELS_FUNCTION_AUX_5=15 18 | uint8 RC_CHANNELS_FUNCTION_PARAM_1=16 19 | uint8 RC_CHANNELS_FUNCTION_PARAM_2=17 20 | uint8 RC_CHANNELS_FUNCTION_PARAM_3_5=18 21 | uint8 RC_CHANNELS_FUNCTION_RATTITUDE=19 22 | uint8 RC_CHANNELS_FUNCTION_KILLSWITCH=20 23 | uint8 RC_CHANNELS_FUNCTION_TRANSITION=21 24 | uint8 RC_CHANNELS_FUNCTION_GEAR=22 25 | uint8 RC_CHANNELS_FUNCTION_ARMSWITCH=23 26 | 27 | uint64 timestamp_last_valid # Timestamp of last valid RC signal 28 | float32[18] channels # Scaled to -1..1 (throttle: 0..1) 29 | uint8 channel_count # Number of valid channels 30 | int8[24] function # Functions mapping 31 | uint8 rssi # Receive signal strength indicator (0-100) 32 | bool signal_lost # Control signal lost, should be checked together with topic timeout 33 | uint32 frame_drop_count # Number of dropped frames 34 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/RcParameterMap.msg: -------------------------------------------------------------------------------- 1 | uint8 RC_PARAM_MAP_NCHAN = 3 # This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h 2 | uint8 PARAM_ID_LEN = 16 # corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 3 | 4 | bool[3] valid #true for RC-Param channels which are mapped to a param 5 | int32[3] param_index # corresponding param index, this field is ignored if set to -1, in this case param_id will be used 6 | char[51] param_id # MAP_NCHAN * (ID_LEN + 1) chars, corresponding param id, null terminated 7 | float32[3] scale # scale to map the RC input [-1, 1] to a parameter value 8 | float32[3] value0 # initial value around which the parameter value is changed 9 | float32[3] value_min # minimal parameter value 10 | float32[3] value_max # minimal parameter value 11 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/Safety.msg: -------------------------------------------------------------------------------- 1 | bool safety_switch_available # Set to true if a safety switch is connected 2 | bool safety_off # Set to true if safety is off 3 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SatelliteInfo.msg: -------------------------------------------------------------------------------- 1 | uint8 SAT_INFO_MAX_SATELLITES = 20 2 | 3 | uint8 count # Number of satellites in satellite info 4 | uint8[20] svid # Space vehicle ID [1..255], see scheme below 5 | uint8[20] used # 0: Satellite not used, 1: used for navigation 6 | uint8[20] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite 7 | uint8[20] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg. 8 | uint8[20] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. 9 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorAccel.msg: -------------------------------------------------------------------------------- 1 | uint64 integral_dt # integration time 2 | uint64 error_count 3 | float32 x # acceleration in the NED X board axis in m/s^2 4 | float32 y # acceleration in the NED Y board axis in m/s^2 5 | float32 z # acceleration in the NED Z board axis in m/s^2 6 | float32 x_integral # velocity in the NED X board axis in m/s over the integration time frame 7 | float32 y_integral # velocity in the NED Y board axis in m/s over the integration time frame 8 | float32 z_integral # velocity in the NED Z board axis in m/s over the integration time frame 9 | float32 temperature # temperature in degrees celsius 10 | float32 range_m_s2 # range in m/s^2 (+- this value) 11 | float32 scaling 12 | 13 | int16 x_raw 14 | int16 y_raw 15 | int16 z_raw 16 | int16 temperature_raw 17 | 18 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 19 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorBaro.msg: -------------------------------------------------------------------------------- 1 | float32 pressure # static pressure measurement in millibar 2 | float32 altitude # ISA pressure altitude in meters 3 | float32 temperature # static temperature measurement in deg C 4 | uint64 error_count 5 | uint32 device_id # Sensor ID that must be unique for each baro sensor and must not change 6 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorCombined.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor readings in SI-unit form. 3 | # 4 | # These fields are scaled and offset-compensated where possible and do not 5 | # change with board revisions and sensor updates. 6 | # 7 | 8 | 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 9 | 10 | 11 | # gyro timstamp is equal to the timestamp of the message 12 | float32[3] gyro_rad # average angular rate measured in the XYZ body frame in rad/s over the last gyro sampling period 13 | float32 gyro_integral_dt # gyro measurement sampling period in s 14 | 15 | int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp 16 | float32[3] accelerometer_m_s2 # average value acceleration measured in the XYZ body frame in m/s/s over the last accelerometer sampling period 17 | float32 accelerometer_integral_dt # accelerometer measurement sampling period in s 18 | 19 | int32 magnetometer_timestamp_relative # timestamp + magnetometer_timestamp_relative = Magnetometer timestamp 20 | float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss 21 | 22 | int32 baro_timestamp_relative # timestamp + baro_timestamp_relative = Barometer timestamp 23 | float32 baro_alt_meter # Altitude, already temp. comp. 24 | float32 baro_temp_celcius # Temperature in degrees celsius 25 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorCorrection.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Sensor corrections in SI-unit form for the voted sensor 3 | # 4 | 5 | # Corrections for gyro angular rate outputs where corrected_rate = raw_rate * gyro_scale + gyro_offset 6 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 7 | float32[3] gyro_offset # gyro XYZ offsets in the sensor frame in rad/s 8 | float32[3] gyro_scale # gyro XYZ scale factors in the sensor frame 9 | 10 | # Corrections for acceleromter acceleration outputs where corrected_accel = raw_accel * accel_scale + accel_offset 11 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 12 | float32[3] accel_offset # accelerometer XYZ offsets in the sensor frame in m/s/s 13 | float32[3] accel_scale # accelerometer XYZ scale factors in the sensor frame 14 | 15 | # Corrections for barometric pressure outputs where corrected_pressure = raw_pressure * pressure_scale + pressure_offset 16 | # Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame 17 | float32 baro_offset # barometric pressure offsets in the sensor frame in m/s/s 18 | float32 baro_scale # barometric pressure scale factors in the sensor frame 19 | 20 | uint8 selected_gyro_instance # gyro uORB topic instance for the voted sensor 21 | uint8 selected_accel_instance # accelerometer uORB topic instance for the voted sensor 22 | uint8 selected_baro_instance # barometric pressure uORB topic instance for the voted sensor 23 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorGyro.msg: -------------------------------------------------------------------------------- 1 | uint64 integral_dt # integration time 2 | uint64 error_count 3 | float32 x # angular velocity in the NED X board axis in rad/s 4 | float32 y # angular velocity in the NED Y board axis in rad/s 5 | float32 z # angular velocity in the NED Z board axis in rad/s 6 | float32 x_integral # delta angle in the NED X board axis in rad/s in the integration time frame 7 | float32 y_integral # delta angle in the NED Y board axis in rad/s in the integration time frame 8 | float32 z_integral # delta angle in the NED Z board axis in rad/s in the integration time frame 9 | float32 temperature # temperature in degrees celcius 10 | float32 range_rad_s 11 | float32 scaling 12 | 13 | int16 x_raw 14 | int16 y_raw 15 | int16 z_raw 16 | int16 temperature_raw 17 | 18 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 19 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorMag.msg: -------------------------------------------------------------------------------- 1 | uint64 error_count 2 | float32 x 3 | float32 y 4 | float32 z 5 | float32 range_ga 6 | float32 scaling 7 | float32 temperature 8 | 9 | int16 x_raw 10 | int16 y_raw 11 | int16 z_raw 12 | 13 | uint32 device_id # unique device ID for the sensor that does not change between power cycles 14 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SensorPreflight.msg: -------------------------------------------------------------------------------- 1 | # 2 | # Pre-flight sensor check metrics. These will be zero if the vehicle only has one sensor. 3 | # The topic will not be updated when the vehicle is armed 4 | # 5 | float32 accel_inconsistency_m_s_s # magnitude of maximum acceleration difference between IMU instances in (m/s/s). 6 | float32 gyro_inconsistency_rad_s # magnitude of maximum angular rate difference between IMU instances in (rad/s). 7 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/ServorailStatus.msg: -------------------------------------------------------------------------------- 1 | float32 voltage_v # Servo rail voltage in volts 2 | float32 rssi_v # RSSI pin voltage in volts 3 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SubsystemInfo.msg: -------------------------------------------------------------------------------- 1 | uint64 SUBSYSTEM_TYPE_GYRO = 1 2 | uint64 SUBSYSTEM_TYPE_ACC = 2 3 | uint64 SUBSYSTEM_TYPE_MAG = 4 4 | uint64 SUBSYSTEM_TYPE_ABSPRESSURE = 8 5 | uint64 SUBSYSTEM_TYPE_DIFFPRESSURE = 16 6 | uint64 SUBSYSTEM_TYPE_GPS = 32 7 | uint64 SUBSYSTEM_TYPE_OPTICALFLOW = 64 8 | uint64 SUBSYSTEM_TYPE_CVPOSITION = 128 9 | uint64 SUBSYSTEM_TYPE_LASERPOSITION = 256 10 | uint64 SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 512 11 | uint64 SUBSYSTEM_TYPE_ANGULARRATECONTROL = 1024 12 | uint64 SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 2048 13 | uint64 SUBSYSTEM_TYPE_YAWPOSITION = 4096 14 | uint64 SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384 15 | uint64 SUBSYSTEM_TYPE_POSITIONCONTROL = 32768 16 | uint64 SUBSYSTEM_TYPE_MOTORCONTROL = 65536 17 | uint64 SUBSYSTEM_TYPE_RANGEFINDER = 131072 18 | 19 | bool present 20 | bool enabled 21 | bool ok 22 | uint64 subsystem_type 23 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/SystemPower.msg: -------------------------------------------------------------------------------- 1 | float32 voltage5V_v # peripheral 5V rail voltage 2 | uint8 usb_connected # USB is connected when 1 3 | uint8 brick_valid # brick power is good when 1 4 | uint8 servo_valid # servo power is good when 1 5 | uint8 periph_5V_OC # peripheral overcurrent when 1 6 | uint8 hipower_5V_OC # hi power peripheral overcurrent when 1 7 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/TecsStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 TECS_MODE_NORMAL = 0 2 | uint8 TECS_MODE_UNDERSPEED = 1 3 | uint8 TECS_MODE_TAKEOFF = 2 4 | uint8 TECS_MODE_LAND = 3 5 | uint8 TECS_MODE_LAND_THROTTLELIM = 4 6 | uint8 TECS_MODE_BAD_DESCENT = 5 7 | uint8 TECS_MODE_CLIMBOUT = 6 8 | 9 | 10 | float32 altitudeSp 11 | float32 altitude_filtered 12 | float32 flightPathAngleSp 13 | float32 flightPathAngle 14 | float32 flightPathAngleFiltered 15 | float32 airspeedSp 16 | float32 airspeed_filtered 17 | float32 airspeedDerivativeSp 18 | float32 airspeedDerivative 19 | 20 | float32 totalEnergyError 21 | float32 energyDistributionError 22 | float32 totalEnergyRateError 23 | float32 energyDistributionRateError 24 | 25 | float32 throttle_integ 26 | float32 pitch_integ 27 | 28 | uint8 mode 29 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/TelemetryStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0 2 | uint8 TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO = 1 3 | uint8 TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET = 2 4 | uint8 TELEMETRY_STATUS_RADIO_TYPE_WIRE = 3 5 | uint8 TELEMETRY_STATUS_RADIO_TYPE_USB = 4 6 | uint8 TELEMETRY_STATUS_RADIO_TYPE_IRIDIUM = 5 7 | 8 | uint64 heartbeat_time # Time of last received heartbeat from remote system 9 | uint64 telem_time # Time of last received telemetry status packet, 0 for none 10 | uint8 type # type of the radio hardware 11 | uint8 rssi # local signal strength 12 | uint8 remote_rssi # remote signal strength 13 | uint16 rxerrors # receive errors 14 | uint16 fixed # count of error corrected packets 15 | uint8 noise # background noise level 16 | uint8 remote_noise # remote background noise level 17 | uint8 txbuf # how full the tx buffer is as a percentage 18 | uint8 system_id # system id of the remote system 19 | uint8 component_id # component id of the remote system 20 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/TestMotor.msg: -------------------------------------------------------------------------------- 1 | uint8 NUM_MOTOR_OUTPUTS = 8 2 | 3 | uint32 motor_number # number of motor to spin 4 | float32 value # output power, range [0..1] 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/TimeOffset.msg: -------------------------------------------------------------------------------- 1 | uint64 offset_ns # time offset between companion system and PX4, in nanoseconds 2 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/TransponderReport.msg: -------------------------------------------------------------------------------- 1 | uint32 ICAO_address # ICAO address 2 | float64 lat # Latitude, expressed as degrees 3 | float64 lon # Longitude, expressed as degrees 4 | uint8 altitude_type # Type from ADSB_ALTITUDE_TYPE enum 5 | float32 altitude # Altitude(ASL) in meters 6 | float32 heading # Course over ground in radians 7 | float32 hor_velocity # The horizontal velocity in m/s 8 | float32 ver_velocity # The vertical velocity in m/s, positive is up 9 | char[9] callsign # The callsign, 8+null 10 | uint8 emitter_type # Type from ADSB_EMITTER_TYPE enum 11 | uint8 tslc # Time since last communication in seconds 12 | uint16 flags # Flags to indicate various statuses including valid data fields 13 | uint16 squawk # Squawk code 14 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/UavcanParameterRequest.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge request type 2 | uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET 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 # -1 if the param_id field should be used as identifier 6 | uint8 param_type # MAVLink parameter type 7 | int64 int_value # current value if param_type is int-like 8 | float32 real_value # current value if param_type is float-like 9 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/UavcanParameterValue.msg: -------------------------------------------------------------------------------- 1 | # UAVCAN-MAVLink parameter bridge response type 2 | uint8 node_id # UAVCAN node ID mapped from MAVLink component ID 3 | char[17] param_id # MAVLink/UAVCAN parameter name 4 | int16 param_index # parameter index, if known 5 | uint16 param_count # number of parameters exposed by the node 6 | uint8 param_type # MAVLink parameter type 7 | int64 int_value # current value if param_type is int-like 8 | float32 real_value # current value if param_type is float-like 9 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/UlogStream.msg: -------------------------------------------------------------------------------- 1 | # Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA 2 | # mavlink message 3 | 4 | # flags bitmasks 5 | uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked. 6 | # Acked messages are published synchronous: a 7 | # publisher waits for an ack before sending the 8 | # next message 9 | 10 | uint8 length # length of data 11 | uint8 first_message_offset # offset into data where first message starts. This 12 | # can be used for recovery, when a previous message got lost 13 | uint16 sequence # allows determine drops 14 | uint8 flags # see FLAGS_* 15 | uint8[249] data # ulog data 16 | 17 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/UlogStreamAck.msg: -------------------------------------------------------------------------------- 1 | # Ack a previously sent ulog_stream message that had 2 | # the NEED_ACK flag set 3 | 4 | int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the message [ms] 5 | int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms 6 | 7 | uint16 sequence 8 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleAttitude.msg: -------------------------------------------------------------------------------- 1 | # This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use 2 | float32 rollspeed # Angular velocity about body north axis (x) in rad/s 3 | float32 pitchspeed # Angular velocity about body east axis (y) in rad/s 4 | float32 yawspeed # Angular velocity about body down axis (z) in rad/s 5 | float32[4] q # Quaternion (NED) 6 | 7 | # TOPICS vehicle_attitude vehicle_attitude_groundtruth 8 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleAttitudeSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_attitude_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_attitude_setpoint.msg 6 | # mc_virtual_attitude_setpoint.msg 7 | # fw_virtual_attitude_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll_body # body angle in NED frame 13 | float32 pitch_body # body angle in NED frame 14 | float32 yaw_body # body angle in NED frame 15 | 16 | float32 yaw_sp_move_rate # rad/s (commanded by user) 17 | 18 | # For quaternion-based attitude control 19 | float32[4] q_d # Desired quaternion for quaternion control 20 | bool q_d_valid # Set to true if quaternion vector is valid 21 | 22 | float32 thrust # Thrust in Newton the power system should generate 23 | 24 | bool roll_reset_integral # Reset roll integral part (navigation logic change) 25 | bool pitch_reset_integral # Reset pitch integral part (navigation logic change) 26 | bool yaw_reset_integral # Reset yaw integral part (navigation logic change) 27 | 28 | bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway) 29 | bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode) 30 | 31 | bool apply_flaps 32 | 33 | float32 landing_gear 34 | 35 | # WAS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint 36 | # TOPICS vehicle_attitude_setpoint 37 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleCommandAck.msg: -------------------------------------------------------------------------------- 1 | uint8 VEHICLE_RESULT_ACCEPTED = 0 2 | uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1 3 | uint8 VEHICLE_RESULT_DENIED = 2 4 | uint8 VEHICLE_RESULT_UNSUPPORTED = 3 5 | uint8 VEHICLE_RESULT_FAILED = 4 6 | 7 | uint32 ORB_QUEUE_LENGTH = 3 8 | 9 | uint16 command 10 | uint8 result 11 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleControlMode.msg: -------------------------------------------------------------------------------- 1 | 2 | # is set whenever the writing thread stores new data 3 | 4 | bool flag_armed 5 | 6 | bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing 7 | 8 | # XXX needs yet to be set by state machine helper 9 | bool flag_system_hil_enabled 10 | 11 | bool flag_control_manual_enabled # true if manual input is mixed in 12 | bool flag_control_auto_enabled # true if onboard autopilot should act 13 | bool flag_control_offboard_enabled # true if offboard control should be used 14 | bool flag_control_rates_enabled # true if rates are stabilized 15 | bool flag_control_attitude_enabled # true if attitude stabilization is mixed in 16 | bool flag_control_rattitude_enabled # true if rate/attitude stabilization is enabled 17 | bool flag_control_force_enabled # true if force control is mixed in 18 | bool flag_control_acceleration_enabled # true if acceleration is controlled 19 | bool flag_control_velocity_enabled # true if horizontal velocity (implies direction) is controlled 20 | bool flag_control_position_enabled # true if position is controlled 21 | bool flag_control_altitude_enabled # true if altitude is controlled 22 | bool flag_control_climb_rate_enabled # true if climb rate is controlled 23 | bool flag_control_termination_enabled # true if flighttermination is enabled 24 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleForceSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Definition of force (NED) setpoint uORB topic. Typically this can be used 2 | # by a position control app together with an attitude control app. 3 | 4 | 5 | float32 x # in N NED 6 | float32 y # in N NED 7 | float32 z # in N NED 8 | float32 yaw # right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw) 9 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/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 | uint64 time_utc_usec # GPS UTC timestamp, (microseconds) 8 | float64 lat # Latitude, (degrees) 9 | float64 lon # Longitude, (degrees) 10 | float32 alt # Altitude AMSL, (meters) 11 | float64[2] delta_lat_lon # Reset delta for horizontal position coordinates 12 | float32 delta_alt # Reset delta for altitude 13 | uint8 lat_lon_reset_counter # Counter for reset events on horizontal position coordinates 14 | uint8 alt_reset_counter # Counter for reset events on altitude 15 | float32 vel_n # North velocity in NED earth-fixed frame, (metres/sec) 16 | float32 vel_e # East velocity in NED earth-fixed frame, (metres/sec) 17 | float32 vel_d # Down velocity in NED earth-fixed frame, (metres/sec) 18 | float32 yaw # Euler yaw angle relative to NED earth-fixed frame, -PI..+PI, (radians) 19 | float32 eph # Standard deviation of horizontal position error, (metres) 20 | float32 epv # Standard deviation of vertical position error, (metres) 21 | float32 terrain_alt # Terrain altitude WGS84, (metres) 22 | bool terrain_alt_valid # Terrain altitude estimate is valid 23 | bool dead_reckoning # True if this position is estimated through dead-reckoning 24 | float32 pressure_alt # Pressure altitude AMSL, (metres) 25 | 26 | # TOPICS vehicle_global_position vehicle_global_position_groundtruth 27 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleGlobalVelocitySetpoint.msg: -------------------------------------------------------------------------------- 1 | # Velocity setpoint in NED frame 2 | float32 vx # in m/s NED 3 | float32 vy # in m/s NED 4 | float32 vz # in m/s NED 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleGpsPosition.msg: -------------------------------------------------------------------------------- 1 | # GPS position in WGS84 coordinates. 2 | # the auto-generated field 'timestamp' is for the position & velocity (microseconds) 3 | int32 lat # Latitude in 1E-7 degrees 4 | int32 lon # Longitude in 1E-7 degrees 5 | int32 alt # Altitude in 1E-3 meters above MSL, (millimetres) 6 | int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres) 7 | 8 | float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec) 9 | float32 c_variance_rad # GPS course accuracy estimate, (radians) 10 | uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 11 | 12 | float32 eph # GPS horizontal position accuracy (metres) 13 | float32 epv # GPS vertical position accuracy (metres) 14 | 15 | float32 hdop # Horizontal dilution of precision 16 | float32 vdop # Vertical dilution of precision 17 | 18 | int32 noise_per_ms # GPS noise per millisecond 19 | int32 jamming_indicator # indicates jamming is occurring 20 | 21 | float32 vel_m_s # GPS ground speed, (metres/sec) 22 | float32 vel_n_m_s # GPS North velocity, (metres/sec) 23 | float32 vel_e_m_s # GPS East velocity, (metres/sec) 24 | float32 vel_d_m_s # GPS Down velocity, (metres/sec) 25 | float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians) 26 | bool vel_ned_valid # True if NED velocity is valid 27 | 28 | int32 timestamp_time_relative # timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds) 29 | 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 30 | 31 | uint8 satellites_used # Number of satellites used 32 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleLandDetected.msg: -------------------------------------------------------------------------------- 1 | bool landed # true if vehicle is currently landed on the ground 2 | bool freefall # true if vehicle is currently in free-fall 3 | bool ground_contact # true if vehicle has ground contact but is not landed 4 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleLocalPositionSetpoint.msg: -------------------------------------------------------------------------------- 1 | # Local position setpoint in NED frame 2 | 3 | float32 x # in meters NED 4 | float32 y # in meters NED 5 | float32 z # in meters NED 6 | float32 yaw # in radians NED -PI..+PI 7 | float32 vx # in meters/sec 8 | float32 vy # in meters/sec 9 | float32 vz # in meters/sec 10 | float32 acc_x # in meters/(sec*sec) 11 | float32 acc_y # in meters/(sec*sec) 12 | float32 acc_z # in meters/(sec*sec) 13 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleRatesSetpoint.msg: -------------------------------------------------------------------------------- 1 | ############################################################################################### 2 | # The vehicle_rates_setpoint.msg needs to be in sync with the virtual setpoint messages 3 | # 4 | # Please keep the following messages identical; 5 | # vehicle_rates_setpoint.msg 6 | # mc_virtual_rates_setpoint.msg 7 | # fw_virtual_rates_setpoint.msg 8 | # 9 | ############################################################################################### 10 | 11 | 12 | float32 roll # body angular rates in NED frame 13 | float32 pitch # body angular rates in NED frame 14 | float32 yaw # body angular rates in NED frame 15 | float32 thrust # thrust normalized to 0..1 16 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VehicleRoi.msg: -------------------------------------------------------------------------------- 1 | # Vehicle Region Of Interest (ROI) 2 | 3 | uint8 VEHICLE_ROI_NONE = 0 # No region of interest | 4 | uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION | 5 | uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION | 6 | uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location | 7 | uint8 VEHICLE_ROI_TARGET = 4 # Point toward target 8 | uint8 VEHICLE_ROI_ENUM_END = 5 9 | 10 | uint8 mode # ROI mode (see above) 11 | uint32 mission_seq # mission sequence to point to 12 | uint32 target_seq # target sequence to point to 13 | float64 lat # Latitude to point to 14 | float64 lon # Longitude to point to 15 | float32 alt # Altitude to point to 16 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VisionPositionEstimate.msg: -------------------------------------------------------------------------------- 1 | uint32 id # ID of the estimator, commonly the component ID of the incoming message 2 | 3 | uint64 timestamp_received # timestamp when the estimate was received 4 | 5 | float32 x # X position in meters in NED earth-fixed frame 6 | float32 y # Y position in meters in NED earth-fixed frame 7 | float32 z # Z position in meters in NED earth-fixed frame (negative altitude) 8 | 9 | float32 vx # X velocity in meters per second in NED earth-fixed frame 10 | float32 vy # Y velocity in meters per second in NED earth-fixed frame 11 | float32 vz # Z velocity in meters per second in NED earth-fixed frame 12 | 13 | float32[4] q # Estimated attitude as quaternion 14 | 15 | float32 pos_err # position error 1-std for each axis (metres) 16 | float32 ang_err # angular error 1-std for each axis (rad) 17 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/VtolVehicleStatus.msg: -------------------------------------------------------------------------------- 1 | # VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE 2 | uint8 VEHICLE_VTOL_STATE_UNDEFINED = 0 3 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_FW = 1 4 | uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2 5 | uint8 VEHICLE_VTOL_STATE_MC = 3 6 | uint8 VEHICLE_VTOL_STATE_FW = 4 7 | uint8 VEHICLE_VTOL_STATE_EXTERNAL = 5 8 | 9 | bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode 10 | bool vtol_in_trans_mode 11 | bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW 12 | bool vtol_transition_failsafe # vtol in transition failsafe mode 13 | bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode 14 | float32 airspeed_tot # Estimated airspeed over control surfaces 15 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/msg/WindEstimate.msg: -------------------------------------------------------------------------------- 1 | float32 windspeed_north # Wind component in north / X direction 2 | float32 windspeed_east # Wind component in east / Y direction 3 | float32 covariance_north # Uncertainty - set to zero (no uncertainty) if not estimated 4 | float32 covariance_east # Uncertainty - set to zero (no uncertainty) if not estimated 5 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | px4_msgs 5 | 0.0.0 6 | Communication demo between PX4 and ROS2 7 | Javier Isabel 8 | Apache License 2.0 9 | 10 | ament_cmake 11 | 12 | builtin_interfaces 13 | rosidl_default_generators 14 | builtin_interfaces 15 | rosidl_default_runtime 16 | 17 | 18 | ament_cmake 19 | 20 | 21 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/px4_msgs/scripts/copy_and_rename.py: -------------------------------------------------------------------------------- 1 | import os 2 | import sys 3 | 4 | from shutil import copyfile 5 | 6 | print("Number of arguments:", len(sys.argv), "arguments.") 7 | print("Argument List:", str(sys.argv)) 8 | 9 | input_dir = sys.argv[1] 10 | output_dir = sys.argv[2] 11 | 12 | for filename in os.listdir(input_dir): 13 | if ".msg" in filename: 14 | input_file = input_dir + filename 15 | output_file = output_dir + filename.partition(".")[0].title().replace('_','') + ".msg" 16 | copyfile(input_file, output_file) 17 | print "Created " + output_file 18 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/sensor_combined_listener/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(sensor_combined_listener) 4 | 5 | find_package(ament_cmake REQUIRED) 6 | 7 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Wextra -Wpedantic") 8 | 9 | find_package(rclcpp REQUIRED) 10 | find_package(px4_msgs REQUIRED) 11 | 12 | add_executable(sensor_combined_listener 13 | src/sensor_combined_listener.cpp) 14 | 15 | add_executable(sensor_combined_latency 16 | src/sensor_combined_latency.cpp) 17 | 18 | ament_target_dependencies(sensor_combined_listener 19 | px4_msgs 20 | rclcpp) 21 | 22 | ament_target_dependencies(sensor_combined_latency 23 | px4_msgs 24 | rclcpp) 25 | 26 | install(TARGETS 27 | sensor_combined_listener 28 | sensor_combined_latency 29 | DESTINATION bin) 30 | 31 | ament_package() 32 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/sensor_combined_listener/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | sensor_combined_listener 5 | 0.0.0 6 | A simple receiver for the PX4 snesor combined message. 7 | Javier Isabel 8 | Apache License 2.0 9 | 10 | ament_cmake 11 | 12 | rclcpp 13 | px4_msgs 14 | 15 | rclcpp 16 | px4_msgs 17 | 18 | 19 | ament_cmake 20 | 21 | 22 | -------------------------------------------------------------------------------- /px4_to_ros2_PoC/sensor_combined_listener/src/sensor_combined_latency.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | #include "rclcpp/rclcpp.hpp" 17 | #include "px4_msgs/msg/sensor_combined.hpp" 18 | 19 | struct PX4Receiver : public rclcpp::Node{ 20 | PX4Receiver() : Node("px4_receiver_latency"){ 21 | publisher_ = this->create_publisher("latency_measurement_topic"); 22 | subscription_ = this->create_subscription("sensor_combined_topic", 23 | [&](px4_msgs::msg::SensorCombined::UniquePtr msg) { 24 | publisher_->publish(msg); 25 | }); 26 | } 27 | private: 28 | rclcpp::Publisher::SharedPtr publisher_; 29 | rclcpp::Subscription::SharedPtr subscription_; 30 | }; 31 | 32 | int main(int argc, char *argv[]) 33 | { 34 | std::cout << "Starting demo..." << std::endl; 35 | fflush(stdout); 36 | rclcpp::init(argc, argv); 37 | rclcpp::spin(std::make_shared()); 38 | return 0; 39 | } 40 | -------------------------------------------------------------------------------- /sensor_combined_ros1/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(sensor_combined_ros1) 3 | 4 | ## Add support for C++11, supported in ROS Kinetic and newer 5 | # add_definitions(-std=c++11) 6 | 7 | ## Find catkin macros and libraries 8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 9 | ## is used, also find other catkin packages 10 | find_package(catkin REQUIRED COMPONENTS 11 | roscpp 12 | rospy 13 | std_msgs 14 | genmsg 15 | px4_msgs 16 | ) 17 | 18 | ## Generate added messages and services with any dependencies listed here 19 | generate_messages( 20 | DEPENDENCIES 21 | std_msgs 22 | px4_msgs 23 | ) 24 | 25 | ################################### 26 | ## catkin specific configuration ## 27 | ################################### 28 | ## The catkin_package macro generates cmake config files for your package 29 | ## Declare things to be passed to dependent projects 30 | ## INCLUDE_DIRS: uncomment this if you package contains header files 31 | ## LIBRARIES: libraries you create in this project that dependent projects also need 32 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 33 | ## DEPENDS: system dependencies of this project that dependent projects also need 34 | catkin_package( 35 | CATKIN_DEPENDS roscpp rospy std_msgs message_runtime px4_msgs 36 | ) 37 | 38 | ########### 39 | ## Build ## 40 | ########### 41 | 42 | ## Specify additional locations of header files 43 | ## Your package locations should be listed before other locations 44 | # include_directories(include) 45 | include_directories( 46 | ${catkin_INCLUDE_DIRS} 47 | ) 48 | 49 | add_executable(sc_ros1_listener src/listener.cpp) 50 | target_link_libraries(sc_ros1_listener ${catkin_LIBRARIES}) 51 | #add_dependencies(ep1_listener beginner_tutorials_generate_messages_cpp) 52 | install(TARGETS sc_ros1_listener 53 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) 54 | --------------------------------------------------------------------------------