mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
564 lines
24 KiB
C++
564 lines
24 KiB
C++
/****************************************************************************
|
|
*
|
|
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
|
|
*
|
|
* Redistribution and use in source and binary forms, with or without
|
|
* modification, are permitted provided that the following conditions
|
|
* are met:
|
|
*
|
|
* 1. Redistributions of source code must retain the above copyright
|
|
* notice, this list of conditions and the following disclaimer.
|
|
* 2. Redistributions in binary form must reproduce the above copyright
|
|
* notice, this list of conditions and the following disclaimer in
|
|
* the documentation and/or other materials provided with the
|
|
* distribution.
|
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
* used to endorse or promote products derived from this software
|
|
* without specific prior written permission.
|
|
*
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
* POSSIBILITY OF SUCH DAMAGE.
|
|
*
|
|
****************************************************************************/
|
|
|
|
/**
|
|
* @file mavlink_messages.cpp
|
|
* MAVLink 2.0 message formatters implementation.
|
|
*
|
|
* @author Lorenz Meier <lorenz@px4.io>
|
|
* @author Anton Babushkin <anton.babushkin@me.com>
|
|
*/
|
|
|
|
#include "mavlink_main.h"
|
|
#include "mavlink_messages.h"
|
|
#include "mavlink_command_sender.h"
|
|
#include "mavlink_simple_analyzer.h"
|
|
|
|
#include <drivers/drv_pwm_output.h>
|
|
#include <lib/conversion/rotation.h>
|
|
#include <lib/geo/geo.h>
|
|
#include <lib/mathlib/mathlib.h>
|
|
#include <lib/matrix/matrix/math.hpp>
|
|
#include <px4_platform_common/time.h>
|
|
#include <math.h>
|
|
|
|
#include <uORB/Subscription.hpp>
|
|
#include <uORB/SubscriptionMultiArray.hpp>
|
|
#include <uORB/topics/vehicle_status.h>
|
|
|
|
#include "streams/ACTUATOR_OUTPUT_STATUS.hpp"
|
|
#include "streams/ALTITUDE.hpp"
|
|
#include "streams/ATTITUDE.hpp"
|
|
#include "streams/ATTITUDE_QUATERNION.hpp"
|
|
#include "streams/ATTITUDE_TARGET.hpp"
|
|
#include "streams/AUTOPILOT_VERSION.hpp"
|
|
#include "streams/BATTERY_STATUS.hpp"
|
|
#include "streams/CAMERA_IMAGE_CAPTURED.hpp"
|
|
#include "streams/CAMERA_TRIGGER.hpp"
|
|
#include "streams/COMMAND_LONG.hpp"
|
|
#include "streams/COMPONENT_INFORMATION.hpp"
|
|
#include "streams/COMPONENT_METADATA.hpp"
|
|
#include "streams/DISTANCE_SENSOR.hpp"
|
|
#include "streams/EFI_STATUS.hpp"
|
|
#include "streams/ESC_INFO.hpp"
|
|
#include "streams/ESC_STATUS.hpp"
|
|
#include "streams/ESTIMATOR_STATUS.hpp"
|
|
#include "streams/EXTENDED_SYS_STATE.hpp"
|
|
#include "streams/FLIGHT_INFORMATION.hpp"
|
|
#if defined(MAVLINK_MSG_ID_GLOBAL_POSITION)
|
|
#include "streams/GLOBAL_POSITION.hpp"
|
|
#endif //MAVLINK_MSG_ID_GLOBAL_POSITION
|
|
#include "streams/GLOBAL_POSITION_INT.hpp"
|
|
#if defined(MAVLINK_MSG_ID_GNSS_INTEGRITY)
|
|
#include "streams/GNSS_INTEGRITY.hpp"
|
|
#endif
|
|
#include "streams/GPS_GLOBAL_ORIGIN.hpp"
|
|
#include "streams/GPS_RAW_INT.hpp"
|
|
#include "streams/GPS_RTCM_DATA.hpp"
|
|
#include "streams/GPS_STATUS.hpp"
|
|
#include "streams/HEARTBEAT.hpp"
|
|
#include "streams/HIGHRES_IMU.hpp"
|
|
#include "streams/HIL_ACTUATOR_CONTROLS.hpp"
|
|
#include "streams/HIL_STATE_QUATERNION.hpp"
|
|
#include "streams/HOME_POSITION.hpp"
|
|
#include "streams/HYGROMETER_SENSOR.hpp"
|
|
#include "streams/LANDING_TARGET.hpp"
|
|
#include "streams/LOCAL_POSITION_NED.hpp"
|
|
#include "streams/MAG_CAL_REPORT.hpp"
|
|
#include "streams/MANUAL_CONTROL.hpp"
|
|
#include "streams/MOUNT_ORIENTATION.hpp"
|
|
#include "streams/NAV_CONTROLLER_OUTPUT.hpp"
|
|
#include "streams/OBSTACLE_DISTANCE.hpp"
|
|
#include "streams/OPEN_DRONE_ID_BASIC_ID.hpp"
|
|
#include "streams/OPEN_DRONE_ID_LOCATION.hpp"
|
|
#include "streams/OPEN_DRONE_ID_SYSTEM.hpp"
|
|
#include "streams/OPEN_DRONE_ID_ARM_STATUS.hpp"
|
|
#include "streams/OPTICAL_FLOW_RAD.hpp"
|
|
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
|
|
#include "streams/PING.hpp"
|
|
#include "streams/POSITION_TARGET_GLOBAL_INT.hpp"
|
|
#include "streams/POSITION_TARGET_LOCAL_NED.hpp"
|
|
#include "streams/PROTOCOL_VERSION.hpp"
|
|
#include "streams/RAW_RPM.hpp"
|
|
#include "streams/RC_CHANNELS.hpp"
|
|
#include "streams/SCALED_IMU.hpp"
|
|
#include "streams/SCALED_IMU2.hpp"
|
|
#include "streams/SCALED_IMU3.hpp"
|
|
#include "streams/SCALED_PRESSURE.hpp"
|
|
#include "streams/SERVO_OUTPUT_RAW.hpp"
|
|
#include "streams/STATUSTEXT.hpp"
|
|
#include "streams/STORAGE_INFORMATION.hpp"
|
|
#include "streams/SYS_STATUS.hpp"
|
|
#include "streams/SYSTEM_TIME.hpp"
|
|
#include "streams/TIME_ESTIMATE_TO_TARGET.hpp"
|
|
#include "streams/TIMESYNC.hpp"
|
|
#include "streams/VFR_HUD.hpp"
|
|
#include "streams/VIBRATION.hpp"
|
|
#include "streams/WIND_COV.hpp"
|
|
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
|
|
#include "streams/FIGURE_EIGHT_EXECUTION_STATUS.hpp"
|
|
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
|
|
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
|
|
#include "streams/FUEL_STATUS.hpp"
|
|
#endif // MAVLINK_MSG_ID_FUEL_STATUS
|
|
|
|
#ifdef MAVLINK_MSG_ID_AVAILABLE_MODES // Only defined if development.xml is used
|
|
#include "streams/AVAILABLE_MODES.hpp"
|
|
#include "streams/CURRENT_MODE.hpp"
|
|
#endif
|
|
|
|
#if !defined(CONSTRAINED_FLASH)
|
|
# include "streams/ADSB_VEHICLE.hpp"
|
|
# include "streams/AUTOPILOT_STATE_FOR_GIMBAL_DEVICE.hpp"
|
|
# include "streams/BATTERY_INFO.hpp"
|
|
# include "streams/DEBUG.hpp"
|
|
# include "streams/DEBUG_FLOAT_ARRAY.hpp"
|
|
# include "streams/DEBUG_VECT.hpp"
|
|
# include "streams/GIMBAL_DEVICE_ATTITUDE_STATUS.hpp"
|
|
# include "streams/GIMBAL_DEVICE_SET_ATTITUDE.hpp"
|
|
# include "streams/GIMBAL_MANAGER_INFORMATION.hpp"
|
|
# include "streams/GIMBAL_MANAGER_STATUS.hpp"
|
|
# include "streams/GIMBAL_DEVICE_INFORMATION.hpp"
|
|
# include "streams/GPS2_RAW.hpp"
|
|
# include "streams/HIGH_LATENCY2.hpp"
|
|
# include "streams/LINK_NODE_STATUS.hpp"
|
|
# include "streams/NAMED_VALUE_FLOAT.hpp"
|
|
# include "streams/ODOMETRY.hpp"
|
|
# include "streams/SCALED_PRESSURE2.hpp"
|
|
# include "streams/SCALED_PRESSURE3.hpp"
|
|
# include "streams/UAVIONIX_ADSB_OUT_CFG.hpp"
|
|
# include "streams/UAVIONIX_ADSB_OUT_DYNAMIC.hpp"
|
|
#endif // !CONSTRAINED_FLASH
|
|
|
|
// ensure PX4 rotation enum and MAV_SENSOR_ROTATION align
|
|
static_assert(MAV_SENSOR_ROTATION_NONE == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_NONE),
|
|
"Roll: 0, Pitch: 0, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_45 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_45),
|
|
"Roll: 0, Pitch: 0, Yaw: 45");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_90),
|
|
"Roll: 0, Pitch: 0, Yaw: 90");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_135 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_135),
|
|
"Roll: 0, Pitch: 0, Yaw: 135");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_180 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_180),
|
|
"Roll: 0, Pitch: 0, Yaw: 180");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_225 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_225),
|
|
"Roll: 0, Pitch: 0, Yaw: 225");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_270),
|
|
"Roll: 0, Pitch: 0, Yaw: 270");
|
|
static_assert(MAV_SENSOR_ROTATION_YAW_315 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_YAW_315),
|
|
"Roll: 0, Pitch: 0, Yaw: 315");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180),
|
|
"Roll: 180, Pitch: 0, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_YAW_45 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_YAW_45),
|
|
"Roll: 180, Pitch: 0, Yaw: 45");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_YAW_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_YAW_90),
|
|
"Roll: 180, Pitch: 0, Yaw: 90");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_YAW_135 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_YAW_135),
|
|
"Roll: 180, Pitch: 0, Yaw: 135");
|
|
static_assert(MAV_SENSOR_ROTATION_PITCH_180 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_PITCH_180),
|
|
"Roll: 0, Pitch: 180, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_YAW_225 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_YAW_225),
|
|
"Roll: 180, Pitch: 0, Yaw: 225");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_YAW_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_YAW_270),
|
|
"Roll: 180, Pitch: 0, Yaw: 270");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_YAW_315 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_YAW_315),
|
|
"Roll: 180, Pitch: 0, Yaw: 315");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90),
|
|
"Roll: 90, Pitch: 0, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_YAW_45 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_YAW_45),
|
|
"Roll: 90, Pitch: 0, Yaw: 45");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_YAW_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_YAW_90),
|
|
"Roll: 90, Pitch: 0, Yaw: 90");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_YAW_135 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_YAW_135),
|
|
"Roll: 90, Pitch: 0, Yaw: 135");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_270),
|
|
"Roll: 270, Pitch: 0, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270_YAW_45 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_270_YAW_45),
|
|
"Roll: 270, Pitch: 0, Yaw: 45");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270_YAW_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_270_YAW_90),
|
|
"Roll: 270, Pitch: 0, Yaw: 90");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270_YAW_135 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_270_YAW_135),
|
|
"Roll: 270, Pitch: 0, Yaw: 135");
|
|
static_assert(MAV_SENSOR_ROTATION_PITCH_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_PITCH_90),
|
|
"Roll: 0, Pitch: 90, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_PITCH_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_PITCH_270),
|
|
"Roll: 0, Pitch: 270, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_PITCH_180_YAW_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_PITCH_180_YAW_90),
|
|
"Roll: 0, Pitch: 180, Yaw: 90");
|
|
static_assert(MAV_SENSOR_ROTATION_PITCH_180_YAW_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_PITCH_180_YAW_270),
|
|
"Roll: 0, Pitch: 180, Yaw: 270");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_PITCH_90),
|
|
"Roll: 90, Pitch: 90, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_180_PITCH_90),
|
|
"Roll: 180, Pitch: 90, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_270_PITCH_90),
|
|
"Roll: 270, Pitch: 90, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_PITCH_180),
|
|
"Roll: 90, Pitch: 180, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 == static_cast<MAV_SENSOR_ORIENTATION>
|
|
(ROTATION_ROLL_270_PITCH_180), "Roll: 270, Pitch: 180, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_PITCH_270),
|
|
"Roll: 90, Pitch: 270, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 == static_cast<MAV_SENSOR_ORIENTATION>
|
|
(ROTATION_ROLL_180_PITCH_270), "Roll: 180, Pitch: 270, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 == static_cast<MAV_SENSOR_ORIENTATION>
|
|
(ROTATION_ROLL_270_PITCH_270), "Roll: 270, Pitch: 270, Yaw: 0");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 == static_cast<MAV_SENSOR_ORIENTATION>
|
|
(ROTATION_ROLL_90_PITCH_180_YAW_90),
|
|
"Roll: 90, Pitch: 180, Yaw: 90");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_YAW_270 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_YAW_270),
|
|
"Roll: 90, Pitch: 0, Yaw: 270");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 == static_cast<MAV_SENSOR_ORIENTATION>
|
|
(ROTATION_ROLL_90_PITCH_68_YAW_293),
|
|
"Roll: 90, Pitch: 68, Yaw: 293");
|
|
static_assert(MAV_SENSOR_ROTATION_PITCH_315 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_PITCH_315), "Pitch: 315");
|
|
static_assert(MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_ROLL_90_PITCH_315),
|
|
"Roll: 90, Pitch: 315");
|
|
|
|
// Note: Update the number (41, as of writing) below to the number of 'normal' rotation enums in MAVLink spec:
|
|
// https://mavlink.io/en/messages/common.html#MAV_SENSOR_ORIENTATION
|
|
static_assert(41 == ROTATION_MAX, "Keep MAV_SENSOR_ROTATION and PX4 Rotation in sync");
|
|
|
|
static_assert(MAV_SENSOR_ROTATION_CUSTOM == static_cast<MAV_SENSOR_ORIENTATION>(ROTATION_CUSTOM), "Custom Rotation");
|
|
|
|
|
|
static const StreamListItem streams_list[] = {
|
|
#if defined(HEARTBEAT_HPP)
|
|
create_stream_list_item<MavlinkStreamHeartbeat>(),
|
|
#endif // HEARTBEAT_HPP
|
|
#if defined(STATUSTEXT_HPP)
|
|
create_stream_list_item<MavlinkStreamStatustext>(),
|
|
#endif // STATUSTEXT_HPP
|
|
#if defined(COMMAND_LONG_HPP)
|
|
create_stream_list_item<MavlinkStreamCommandLong>(),
|
|
#endif // COMMAND_LONG_HPP
|
|
#if defined(SYS_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamSysStatus>(),
|
|
#endif // SYS_STATUS_HPP
|
|
create_stream_list_item<MavlinkStreamBatteryStatus>(),
|
|
#if defined(BATTERY_INFO_HPP)
|
|
create_stream_list_item<MavlinkStreamBatteryInfo>(),
|
|
#endif // BATTERY_INFO_HPP
|
|
#if defined(HIGHRES_IMU_HPP)
|
|
create_stream_list_item<MavlinkStreamHighresIMU>(),
|
|
#endif // HIGHRES_IMU_HPP
|
|
#if defined(SCALED_IMU_HPP)
|
|
create_stream_list_item<MavlinkStreamScaledIMU>(),
|
|
#endif // SCALED_IMU_HPP
|
|
#if defined(SCALED_IMU2_HPP)
|
|
create_stream_list_item<MavlinkStreamScaledIMU2>(),
|
|
#endif // SCALED_IMU2_HPP
|
|
#if defined(SCALED_IMU3_HPP)
|
|
create_stream_list_item<MavlinkStreamScaledIMU3>(),
|
|
#endif // SCALED_IMU3_HPP
|
|
#if defined(SCALED_PRESSURE_HPP)
|
|
create_stream_list_item<MavlinkStreamScaledPressure>(),
|
|
#endif // SCALED_PRESSURE
|
|
#if defined(SCALED_PRESSURE2_HPP)
|
|
create_stream_list_item<MavlinkStreamScaledPressure2>(),
|
|
#endif // SCALED_PRESSURE2
|
|
#if defined(SCALED_PRESSURE3_HPP)
|
|
create_stream_list_item<MavlinkStreamScaledPressure3>(),
|
|
#endif // SCALED_PRESSURE3
|
|
#if defined(ACTUATOR_OUTPUT_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamActuatorOutputStatus>(),
|
|
#endif // ACTUATOR_OUTPUT_STATUS_HPP
|
|
#if defined(ATTITUDE_HPP)
|
|
create_stream_list_item<MavlinkStreamAttitude>(),
|
|
#endif // ATTITUDE_HPP
|
|
#if defined(ATTITUDE_QUATERNION_HPP)
|
|
create_stream_list_item<MavlinkStreamAttitudeQuaternion>(),
|
|
#endif // ATTITUDE_QUATERNION_HPP
|
|
#if defined(VFR_HUD_HPP)
|
|
create_stream_list_item<MavlinkStreamVFRHUD>(),
|
|
#endif // VFR_HUD_HPP
|
|
#if defined(GPS_GLOBAL_ORIGIN_HPP)
|
|
create_stream_list_item<MavlinkStreamGpsGlobalOrigin>(),
|
|
#endif // GPS_GLOBAL_ORIGIN_HPP
|
|
#if defined(GPS_RAW_INT_HPP)
|
|
create_stream_list_item<MavlinkStreamGPSRawInt>(),
|
|
#endif // GPS_RAW_INT_HPP
|
|
#if defined(GPS2_RAW_HPP)
|
|
create_stream_list_item<MavlinkStreamGPS2Raw>(),
|
|
#endif // GPS2_RAW_HPP
|
|
#if defined(SYSTEM_TIME_HPP)
|
|
create_stream_list_item<MavlinkStreamSystemTime>(),
|
|
#endif // SYSTEM_TIME_HPP
|
|
#if defined(TIME_ESTIMATE_TO_TARGET_HPP)
|
|
create_stream_list_item<MavlinkStreamTimeEstimateToTarget>(),
|
|
#endif // TIME_ESTIMATE_TO_TARGET_HPP
|
|
#if defined(TIMESYNC_HPP)
|
|
create_stream_list_item<MavlinkStreamTimesync>(),
|
|
#endif // TIMESYNC_HPP
|
|
#if defined(GLOBAL_POSITION_INT_HPP)
|
|
create_stream_list_item<MavlinkStreamGlobalPositionInt>(),
|
|
#endif // GLOBAL_POSITION_INT_HPP
|
|
#if defined(LANDING_TARGET_HPP)
|
|
create_stream_list_item<MavlinkStreamLandingTarget>(),
|
|
#endif
|
|
#if defined(LOCAL_POSITION_NED_HPP)
|
|
create_stream_list_item<MavlinkStreamLocalPositionNED>(),
|
|
#endif // LOCAL_POSITION_NED_HPP
|
|
#if defined(MAG_CAL_REPORT_HPP)
|
|
create_stream_list_item<MavlinkStreamMagCalReport>(),
|
|
#endif // MAG_CAL_REPORT_HPP
|
|
#if defined(ODOMETRY_HPP)
|
|
create_stream_list_item<MavlinkStreamOdometry>(),
|
|
#endif // ODOMETRY_HPP
|
|
#if defined(ESTIMATOR_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamEstimatorStatus>(),
|
|
#endif // ESTIMATOR_STATUS_HPP
|
|
#if defined(VIBRATION_HPP)
|
|
create_stream_list_item<MavlinkStreamVibration>(),
|
|
#endif // VIBRATION_HPP
|
|
#if defined(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_HPP)
|
|
create_stream_list_item<MavlinkStreamAutopilotStateForGimbalDevice>(),
|
|
#endif // AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_HPP
|
|
#if defined(GIMBAL_DEVICE_ATTITUDE_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamGimbalDeviceAttitudeStatus>(),
|
|
#endif // GIMBAL_DEVICE_ATTITUDE_STATUS_HPP
|
|
#if defined(GIMBAL_MANAGER_INFORMATION_HPP)
|
|
create_stream_list_item<MavlinkStreamGimbalManagerInformation>(),
|
|
#endif // GIMBAL_MANAGER_INFORMATION_HPP
|
|
#if defined(GIMBAL_DEVICE_INFORMATION_HPP)
|
|
create_stream_list_item<MavlinkStreamGimbalDeviceInformation>(),
|
|
#endif // GIMBAL_DEVICE_INFORMATION_HPP
|
|
#if defined(GIMBAL_MANAGER_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamGimbalManagerStatus>(),
|
|
#endif // GIMBAL_MANAGER_STATUS_HPP
|
|
#if defined(GIMBAL_DEVICE_SET_ATTITUDE_HPP)
|
|
create_stream_list_item<MavlinkStreamGimbalDeviceSetAttitude>(),
|
|
#endif // GIMBAL_DEVICE_SET_ATTITUDE_HPP
|
|
#if defined(HOME_POSITION_HPP)
|
|
create_stream_list_item<MavlinkStreamHomePosition>(),
|
|
#endif // HOME_POSITION_HPP
|
|
#if defined(HYGROMETER_SENSOR_HPP)
|
|
create_stream_list_item<MavlinkStreamHygrometerSensor>(),
|
|
#endif // HYGROMETER_SENSOR_HPP
|
|
#if defined(SERVO_OUTPUT_RAW_HPP)
|
|
create_stream_list_item<MavlinkStreamServoOutputRaw<0> >(),
|
|
create_stream_list_item<MavlinkStreamServoOutputRaw<1> >(),
|
|
#endif // SERVO_OUTPUT_RAW_HPP
|
|
#if defined(HIL_ACTUATOR_CONTROLS_HPP)
|
|
create_stream_list_item<MavlinkStreamHILActuatorControls>(),
|
|
#endif // HIL_ACTUATOR_CONTROLS_HPP
|
|
#if defined(POSITION_TARGET_GLOBAL_INT_HPP)
|
|
create_stream_list_item<MavlinkStreamPositionTargetGlobalInt>(),
|
|
#endif // POSITION_TARGET_GLOBAL_INT_HPP
|
|
#if defined(POSITION_TARGET_LOCAL_NED_HPP)
|
|
create_stream_list_item<MavlinkStreamPositionTargetLocalNed>(),
|
|
#endif // POSITION_TARGET_LOCAL_NED_HPP
|
|
#if defined(ATTITUDE_TARGET_HPP)
|
|
create_stream_list_item<MavlinkStreamAttitudeTarget>(),
|
|
#endif // ATTITUDE_TARGET_HPP
|
|
#if defined(RC_CHANNELS_HPP)
|
|
create_stream_list_item<MavlinkStreamRCChannels>(),
|
|
#endif // RC_CHANNELS_HPP
|
|
#if defined(MANUAL_CONTROL_HPP)
|
|
create_stream_list_item<MavlinkStreamManualControl>(),
|
|
#endif // MANUAL_CONTROL_HPP
|
|
#if defined(OPTICAL_FLOW_RAD_HPP)
|
|
create_stream_list_item<MavlinkStreamOpticalFlowRad>(),
|
|
#endif // OPTICAL_FLOW_RAD_HPP
|
|
#if defined(NAMED_VALUE_FLOAT_HPP)
|
|
create_stream_list_item<MavlinkStreamNamedValueFloat>(),
|
|
#endif // NAMED_VALUE_FLOAT_HPP
|
|
#if defined(DEBUG_HPP)
|
|
create_stream_list_item<MavlinkStreamDebug>(),
|
|
#endif // DEBUG_HPP
|
|
#if defined(DEBUG_VECT_HPP)
|
|
create_stream_list_item<MavlinkStreamDebugVect>(),
|
|
#endif // DEBUG_VECT_HPP
|
|
#if defined(DEBUG_FLOAT_ARRAY_HPP)
|
|
create_stream_list_item<MavlinkStreamDebugFloatArray>(),
|
|
#endif // DEBUG_FLOAT_ARRAY_HPP
|
|
#if defined(NAV_CONTROLLER_OUTPUT_HPP)
|
|
create_stream_list_item<MavlinkStreamNavControllerOutput>(),
|
|
#endif // NAV_CONTROLLER_OUTPUT_HPP
|
|
#if defined(CAMERA_TRIGGER_HPP)
|
|
create_stream_list_item<MavlinkStreamCameraTrigger>(),
|
|
#endif // CAMERA_TRIGGER_HPP
|
|
#if defined(CAMERA_IMAGE_CAPTURED_HPP)
|
|
create_stream_list_item<MavlinkStreamCameraImageCaptured>(),
|
|
#endif // CAMERA_IMAGE_CAPTURED_HPP
|
|
#if defined(DISTANCE_SENSOR_HPP)
|
|
create_stream_list_item<MavlinkStreamDistanceSensor>(),
|
|
#endif // DISTANCE_SENSOR_HPP
|
|
#if defined(EXTENDED_SYS_STATE_HPP)
|
|
create_stream_list_item<MavlinkStreamExtendedSysState>(),
|
|
#endif // EXTENDED_SYS_STATE_HPP
|
|
#if defined(ALTITUDE_HPP)
|
|
create_stream_list_item<MavlinkStreamAltitude>(),
|
|
#endif // ALTITUDE_HPP
|
|
#if defined(ADSB_VEHICLE_HPP)
|
|
create_stream_list_item<MavlinkStreamADSBVehicle>(),
|
|
#endif // ADSB_VEHICLE_HPP
|
|
#if defined(COLLISION_HPP)
|
|
create_stream_list_item<MavlinkStreamCollision>(),
|
|
#endif // COLLISION_HPP
|
|
#if defined(WIND_COV_HPP)
|
|
create_stream_list_item<MavlinkStreamWindCov>(),
|
|
#endif // WIND_COV_HPP
|
|
#if defined(MOUNT_ORIENTATION_HPP)
|
|
create_stream_list_item<MavlinkStreamMountOrientation>(),
|
|
#endif // MOUNT_ORIENTATION_HPP
|
|
#if defined(HIGH_LATENCY2_HPP)
|
|
create_stream_list_item<MavlinkStreamHighLatency2>(),
|
|
#endif // HIGH_LATENCY2_HPP
|
|
#if defined(HIL_STATE_QUATERNION_HPP)
|
|
create_stream_list_item<MavlinkStreamHILStateQuaternion>(),
|
|
#endif // HIL_STATE_QUATERNION_HPP
|
|
#if defined(PING_HPP)
|
|
create_stream_list_item<MavlinkStreamPing>(),
|
|
#endif // PING_HPP
|
|
#if defined(ORBIT_EXECUTION_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamOrbitStatus>(),
|
|
#endif // ORBIT_EXECUTION_STATUS_HPP
|
|
#if defined(FIGURE_EIGHT_EXECUTION_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamFigureEightStatus>(),
|
|
#endif // FIGURE_EIGHT_EXECUTION_STATUS_HPP
|
|
#if defined(OBSTACLE_DISTANCE_HPP)
|
|
create_stream_list_item<MavlinkStreamObstacleDistance>(),
|
|
#endif // OBSTACLE_DISTANCE_HPP
|
|
#if defined(OPEN_DRONE_ID_BASIC_ID_HPP)
|
|
create_stream_list_item<MavlinkStreamOpenDroneIdBasicId>(),
|
|
#endif // OPEN_DRONE_ID_BASIC_ID_HPP
|
|
#if defined(OPEN_DRONE_ID_LOCATION_HPP)
|
|
create_stream_list_item<MavlinkStreamOpenDroneIdLocation>(),
|
|
#endif // OPEN_DRONE_ID_LOCATION_HPP
|
|
#if defined(OPEN_DRONE_ID_SYSTEM_HPP)
|
|
create_stream_list_item<MavlinkStreamOpenDroneIdSystem>(),
|
|
#endif // OPEN_DRONE_ID_SYSTEM_HPP
|
|
#if defined(OPEN_DRONE_ID_ARM_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamOpenDroneIdArmStatus>(),
|
|
#endif // OPEN_DRONE_ID_ARM_STATUS_HPP
|
|
#if defined(ESC_INFO_HPP)
|
|
create_stream_list_item<MavlinkStreamESCInfo>(),
|
|
#endif // ESC_INFO_HPP
|
|
#if defined(ESC_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamESCStatus>(),
|
|
#endif // ESC_STATUS_HPP
|
|
#if defined(AUTOPILOT_VERSION_HPP)
|
|
create_stream_list_item<MavlinkStreamAutopilotVersion>(),
|
|
#endif // AUTOPILOT_VERSION_HPP
|
|
#if defined(PROTOCOL_VERSION_HPP)
|
|
create_stream_list_item<MavlinkStreamProtocolVersion>(),
|
|
#endif // PROTOCOL_VERSION_HPP
|
|
#if defined(FLIGHT_INFORMATION_HPP)
|
|
create_stream_list_item<MavlinkStreamFlightInformation>(),
|
|
#endif // FLIGHT_INFORMATION_HPP
|
|
#if defined(FUEL_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamFuelStatus>(),
|
|
#endif // FUEL_STATUS_HPP
|
|
#if defined(GPS_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamGPSStatus>(),
|
|
#endif // GPS_STATUS_HPP
|
|
#if defined(LINK_NODE_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamLinkNodeStatus>(),
|
|
#endif // LINK_NODE_STATUS_HPP
|
|
#if defined(STORAGE_INFORMATION_HPP)
|
|
create_stream_list_item<MavlinkStreamStorageInformation>(),
|
|
#endif // STORAGE_INFORMATION_HPP
|
|
#if defined(COMPONENT_INFORMATION_HPP)
|
|
create_stream_list_item<MavlinkStreamComponentInformation>(),
|
|
#endif // COMPONENT_INFORMATION_HPP
|
|
#if defined(COMPONENT_METADATA_HPP)
|
|
create_stream_list_item<MavlinkStreamComponentMetadata>(),
|
|
#endif // COMPONENT_METADATA_HPP
|
|
#if defined(RAW_RPM_HPP)
|
|
create_stream_list_item<MavlinkStreamRawRpm>(),
|
|
#endif // RAW_RPM_HPP
|
|
#if defined(EFI_STATUS_HPP)
|
|
create_stream_list_item<MavlinkStreamEfiStatus>(),
|
|
#endif // EFI_STATUS_HPP
|
|
#if defined(GPS_RTCM_DATA_HPP)
|
|
create_stream_list_item<MavlinkStreamGPSRTCMData>(),
|
|
#endif // GPS_RTCM_DATA_HPP
|
|
#if defined(UAVIONIX_ADSB_OUT_CFG_HPP)
|
|
create_stream_list_item<MavlinkStreamUavionixADSBOutCfg>(),
|
|
#endif // UAVIONIX_ADSB_OUT_CFG_HPP
|
|
#if defined(UAVIONIX_ADSB_OUT_DYNAMIC_HPP)
|
|
create_stream_list_item<MavlinkStreamUavionixADSBOutDynamic>(),
|
|
#endif // UAVIONIX_ADSB_OUT_DYNAMIC_HPP
|
|
#if defined(GNSS_INTEGRITY_HPP)
|
|
create_stream_list_item<MavlinkStreamGNSSIntegrity>(),
|
|
#endif // GNSS_INTEGRITY_HPP
|
|
#if defined(AVAILABLE_MODES_HPP)
|
|
create_stream_list_item<MavlinkStreamAvailableModes>(),
|
|
#endif // AVAILABLE_MODES_HPP
|
|
#if defined(CURRENT_MODE_HPP)
|
|
create_stream_list_item<MavlinkStreamCurrentMode>(),
|
|
#endif // CURRENT_MODE_HPP
|
|
#if defined(GLOBAL_POSITION_HPP)
|
|
create_stream_list_item<MavlinkStreamGLobalPosition>(),
|
|
#endif // GLOBAL_POSITION_HPP
|
|
};
|
|
|
|
const char *get_stream_name(const uint16_t msg_id)
|
|
{
|
|
// search for stream with specified msg id in supported streams list
|
|
for (const auto &stream : streams_list) {
|
|
if (msg_id == stream.get_id()) {
|
|
return stream.get_name();
|
|
}
|
|
}
|
|
|
|
return nullptr;
|
|
}
|
|
|
|
MavlinkStream *create_mavlink_stream(const char *stream_name, Mavlink *mavlink)
|
|
{
|
|
// search for stream with specified name in supported streams list
|
|
if (stream_name != nullptr) {
|
|
for (const auto &stream : streams_list) {
|
|
if (strcmp(stream_name, stream.get_name()) == 0) {
|
|
return stream.new_instance(mavlink);
|
|
}
|
|
}
|
|
}
|
|
|
|
return nullptr;
|
|
}
|
|
|
|
MavlinkStream *create_mavlink_stream(const uint16_t msg_id, Mavlink *mavlink)
|
|
{
|
|
// search for stream with specified name in supported streams list
|
|
for (const auto &stream : streams_list) {
|
|
if (msg_id == stream.get_id()) {
|
|
return stream.new_instance(mavlink);
|
|
}
|
|
}
|
|
|
|
return nullptr;
|
|
}
|