diff --git a/lib/main/MAVLink/common/common.h b/lib/main/MAVLink/common/common.h index 4f417caf97..1014966516 100755 --- a/lib/main/MAVLink/common/common.h +++ b/lib/main/MAVLink/common/common.h @@ -11,7 +11,7 @@ #endif #undef MAVLINK_THIS_XML_IDX -#define MAVLINK_THIS_XML_IDX 1 +#define MAVLINK_THIS_XML_IDX 0 #ifdef __cplusplus extern "C" { @@ -20,11 +20,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 0, 0, 27, 25, 0, 0, 0, 0, 0, 72, 26, 181, 225, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 81, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 63, 182, 40, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 19, 254, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 36, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 24, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 7, 0, 27, 25, 0, 0, 0, 0, 0, 72, 26, 181, 225, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 4, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 81, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 63, 182, 40, 42, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 19, 254, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 167, 183, 119, 191, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 47, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 151, 35, 150, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 81, 8, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 117, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 137, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 132, 0, 15, 3, 0, 0, 0, 0, 0, 167, 183, 119, 191, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 14, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 47, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 189, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 151, 35, 150, 179, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 81, 8, 204, 49, 170, 44, 83, 46, 0} #endif #include "../protocol.h" @@ -42,7 +42,7 @@ typedef enum MAV_AUTOPILOT MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */ MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ - MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ + MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org | */ MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ @@ -51,22 +51,24 @@ typedef enum MAV_AUTOPILOT MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ - MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */ + MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://px4.io/ | */ MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */ - MAV_AUTOPILOT_ENUM_END=18, /* | */ + MAV_AUTOPILOT_SMARTAP=18, /* SmartAP Autopilot - http://sky-drones.com | */ + MAV_AUTOPILOT_AIRRAILS=19, /* AirRails - http://uaventure.com | */ + MAV_AUTOPILOT_ENUM_END=20, /* | */ } MAV_AUTOPILOT; #endif -/** @brief */ +/** @brief MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA). */ #ifndef HAVE_ENUM_MAV_TYPE #define HAVE_ENUM_MAV_TYPE typedef enum MAV_TYPE { - MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ + MAV_TYPE_GENERIC=0, /* Generic micro air vehicle | */ MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ @@ -92,9 +94,16 @@ typedef enum MAV_TYPE MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */ MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */ MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ - MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */ - MAV_TYPE_ADSB=27, /* Onboard ADSB peripheral | */ - MAV_TYPE_ENUM_END=28, /* | */ + MAV_TYPE_GIMBAL=26, /* Gimbal | */ + MAV_TYPE_ADSB=27, /* ADSB system | */ + MAV_TYPE_PARAFOIL=28, /* Steerable, nonrigid airfoil | */ + MAV_TYPE_DODECAROTOR=29, /* Dodecarotor | */ + MAV_TYPE_CAMERA=30, /* Camera | */ + MAV_TYPE_CHARGING_STATION=31, /* Charging station | */ + MAV_TYPE_FLARM=32, /* FLARM collision avoidance system | */ + MAV_TYPE_SERVO=33, /* Servo | */ + MAV_TYPE_ODID=34, /* Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. | */ + MAV_TYPE_ENUM_END=35, /* | */ } MAV_TYPE; #endif @@ -112,6 +121,29 @@ typedef enum FIRMWARE_VERSION_TYPE } FIRMWARE_VERSION_TYPE; #endif +/** @brief Flags to report failure cases over the high latency telemtry. */ +#ifndef HAVE_ENUM_HL_FAILURE_FLAG +#define HAVE_ENUM_HL_FAILURE_FLAG +typedef enum HL_FAILURE_FLAG +{ + HL_FAILURE_FLAG_GPS=1, /* GPS failure. | */ + HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE=2, /* Differential pressure sensor failure. | */ + HL_FAILURE_FLAG_ABSOLUTE_PRESSURE=4, /* Absolute pressure sensor failure. | */ + HL_FAILURE_FLAG_3D_ACCEL=8, /* Accelerometer sensor failure. | */ + HL_FAILURE_FLAG_3D_GYRO=16, /* Gyroscope sensor failure. | */ + HL_FAILURE_FLAG_3D_MAG=32, /* Magnetometer sensor failure. | */ + HL_FAILURE_FLAG_TERRAIN=64, /* Terrain subsystem failure. | */ + HL_FAILURE_FLAG_BATTERY=128, /* Battery failure/critical low battery. | */ + HL_FAILURE_FLAG_RC_RECEIVER=256, /* RC receiver failure/no rc connection. | */ + HL_FAILURE_FLAG_OFFBOARD_LINK=512, /* Offboard link failure. | */ + HL_FAILURE_FLAG_ENGINE=1024, /* Engine failure. | */ + HL_FAILURE_FLAG_GEOFENCE=2048, /* Geofence violation. | */ + HL_FAILURE_FLAG_ESTIMATOR=4096, /* Estimator failure, for example measurement rejection or large variances. | */ + HL_FAILURE_FLAG_MISSION=8192, /* Mission failure. | */ + HL_FAILURE_FLAG_ENUM_END=8193, /* | */ +} HL_FAILURE_FLAG; +#endif + /** @brief These flags encode the MAV mode. */ #ifndef HAVE_ENUM_MAV_MODE_FLAG #define HAVE_ENUM_MAV_MODE_FLAG @@ -120,7 +152,7 @@ typedef enum MAV_MODE_FLAG MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ - MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ + MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies waypoints / mission items. | */ MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ @@ -136,7 +168,7 @@ typedef enum MAV_MODE_FLAG_DECODE_POSITION { MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ - MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ + MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixth bit: 00000100 | */ MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ @@ -146,7 +178,7 @@ typedef enum MAV_MODE_FLAG_DECODE_POSITION } MAV_MODE_FLAG_DECODE_POSITION; #endif -/** @brief Override command, pauses current mission execution and moves immediately to a position */ +/** @brief Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution. */ #ifndef HAVE_ENUM_MAV_GOTO #define HAVE_ENUM_MAV_GOTO typedef enum MAV_GOTO @@ -170,12 +202,12 @@ typedef enum MAV_MODE MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints) | */ MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints) | */ MAV_MODE_ENUM_END=221, /* | */ } MAV_MODE; #endif @@ -193,47 +225,145 @@ typedef enum MAV_STATE MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ - MAV_STATE_ENUM_END=8, /* | */ + MAV_STATE_FLIGHT_TERMINATION=8, /* System is terminating itself. | */ + MAV_STATE_ENUM_END=9, /* | */ } MAV_STATE; #endif -/** @brief */ +/** @brief Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). + Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. + When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded. */ #ifndef HAVE_ENUM_MAV_COMPONENT #define HAVE_ENUM_MAV_COMPONENT typedef enum MAV_COMPONENT { - MAV_COMP_ID_ALL=0, /* | */ - MAV_COMP_ID_CAMERA=100, /* | */ - MAV_COMP_ID_SERVO1=140, /* | */ - MAV_COMP_ID_SERVO2=141, /* | */ - MAV_COMP_ID_SERVO3=142, /* | */ - MAV_COMP_ID_SERVO4=143, /* | */ - MAV_COMP_ID_SERVO5=144, /* | */ - MAV_COMP_ID_SERVO6=145, /* | */ - MAV_COMP_ID_SERVO7=146, /* | */ - MAV_COMP_ID_SERVO8=147, /* | */ - MAV_COMP_ID_SERVO9=148, /* | */ - MAV_COMP_ID_SERVO10=149, /* | */ - MAV_COMP_ID_SERVO11=150, /* | */ - MAV_COMP_ID_SERVO12=151, /* | */ - MAV_COMP_ID_SERVO13=152, /* | */ - MAV_COMP_ID_SERVO14=153, /* | */ - MAV_COMP_ID_GIMBAL=154, /* | */ - MAV_COMP_ID_LOG=155, /* | */ - MAV_COMP_ID_ADSB=156, /* | */ - MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links | */ - MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol | */ - MAV_COMP_ID_QX1_GIMBAL=159, /* | */ - MAV_COMP_ID_MAPPER=180, /* | */ - MAV_COMP_ID_MISSIONPLANNER=190, /* | */ - MAV_COMP_ID_PATHPLANNER=195, /* | */ - MAV_COMP_ID_IMU=200, /* | */ - MAV_COMP_ID_IMU_2=201, /* | */ - MAV_COMP_ID_IMU_3=202, /* | */ - MAV_COMP_ID_GPS=220, /* | */ - MAV_COMP_ID_UDP_BRIDGE=240, /* | */ - MAV_COMP_ID_UART_BRIDGE=241, /* | */ - MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ + MAV_COMP_ID_ALL=0, /* Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message. | */ + MAV_COMP_ID_AUTOPILOT1=1, /* System flight controller component ("autopilot"). Only one autopilot is expected in a particular system. | */ + MAV_COMP_ID_USER1=25, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER2=26, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER3=27, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER4=28, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER5=29, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER6=30, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER7=31, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER8=32, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER9=33, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER10=34, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER11=35, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER12=36, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER13=37, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER14=38, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER15=39, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER16=40, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER17=41, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER18=42, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER19=43, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER20=44, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER21=45, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER22=46, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER23=47, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER24=48, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER25=49, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER26=50, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER27=51, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER28=52, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER29=53, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER30=54, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER31=55, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER32=56, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER33=57, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER34=58, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER35=59, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER36=60, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER37=61, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER38=62, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER39=63, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER40=64, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER41=65, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER42=66, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER43=67, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_TELEMETRY_RADIO=68, /* Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages). | */ + MAV_COMP_ID_USER45=69, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER46=70, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER47=71, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER48=72, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER49=73, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER50=74, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER51=75, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER52=76, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER53=77, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER54=78, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER55=79, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER56=80, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER57=81, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER58=82, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER59=83, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER60=84, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER61=85, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER62=86, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER63=87, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER64=88, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER65=89, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER66=90, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER67=91, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER68=92, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER69=93, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER70=94, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER71=95, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER72=96, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER73=97, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER74=98, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_USER75=99, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ + MAV_COMP_ID_CAMERA=100, /* Camera #1. | */ + MAV_COMP_ID_CAMERA2=101, /* Camera #2. | */ + MAV_COMP_ID_CAMERA3=102, /* Camera #3. | */ + MAV_COMP_ID_CAMERA4=103, /* Camera #4. | */ + MAV_COMP_ID_CAMERA5=104, /* Camera #5. | */ + MAV_COMP_ID_CAMERA6=105, /* Camera #6. | */ + MAV_COMP_ID_SERVO1=140, /* Servo #1. | */ + MAV_COMP_ID_SERVO2=141, /* Servo #2. | */ + MAV_COMP_ID_SERVO3=142, /* Servo #3. | */ + MAV_COMP_ID_SERVO4=143, /* Servo #4. | */ + MAV_COMP_ID_SERVO5=144, /* Servo #5. | */ + MAV_COMP_ID_SERVO6=145, /* Servo #6. | */ + MAV_COMP_ID_SERVO7=146, /* Servo #7. | */ + MAV_COMP_ID_SERVO8=147, /* Servo #8. | */ + MAV_COMP_ID_SERVO9=148, /* Servo #9. | */ + MAV_COMP_ID_SERVO10=149, /* Servo #10. | */ + MAV_COMP_ID_SERVO11=150, /* Servo #11. | */ + MAV_COMP_ID_SERVO12=151, /* Servo #12. | */ + MAV_COMP_ID_SERVO13=152, /* Servo #13. | */ + MAV_COMP_ID_SERVO14=153, /* Servo #14. | */ + MAV_COMP_ID_GIMBAL=154, /* Gimbal #1. | */ + MAV_COMP_ID_LOG=155, /* Logging component. | */ + MAV_COMP_ID_ADSB=156, /* Automatic Dependent Surveillance-Broadcast (ADS-B) component. | */ + MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links. | */ + MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. | */ + MAV_COMP_ID_QX1_GIMBAL=159, /* Gimbal ID for QX1. | */ + MAV_COMP_ID_FLARM=160, /* FLARM collision alert component. | */ + MAV_COMP_ID_GIMBAL2=171, /* Gimbal #2. | */ + MAV_COMP_ID_GIMBAL3=172, /* Gimbal #3. | */ + MAV_COMP_ID_GIMBAL4=173, /* Gimbal #4 | */ + MAV_COMP_ID_GIMBAL5=174, /* Gimbal #5. | */ + MAV_COMP_ID_GIMBAL6=175, /* Gimbal #6. | */ + MAV_COMP_ID_MISSIONPLANNER=190, /* Component that can generate/supply a mission flight plan (e.g. GCS or developer API). | */ + MAV_COMP_ID_ONBOARD_COMPUTER=191, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */ + MAV_COMP_ID_PATHPLANNER=195, /* Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). | */ + MAV_COMP_ID_OBSTACLE_AVOIDANCE=196, /* Component that plans a collision free path between two points. | */ + MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY=197, /* Component that provides position estimates using VIO techniques. | */ + MAV_COMP_ID_PAIRING_MANAGER=198, /* Component that manages pairing of vehicle and GCS. | */ + MAV_COMP_ID_IMU=200, /* Inertial Measurement Unit (IMU) #1. | */ + MAV_COMP_ID_IMU_2=201, /* Inertial Measurement Unit (IMU) #2. | */ + MAV_COMP_ID_IMU_3=202, /* Inertial Measurement Unit (IMU) #3. | */ + MAV_COMP_ID_GPS=220, /* GPS #1. | */ + MAV_COMP_ID_GPS2=221, /* GPS #2. | */ + MAV_COMP_ID_ODID_TXRX_1=236, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */ + MAV_COMP_ID_ODID_TXRX_2=237, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */ + MAV_COMP_ID_ODID_TXRX_3=238, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */ + MAV_COMP_ID_UDP_BRIDGE=240, /* Component to bridge MAVLink to UDP (i.e. from a UART). | */ + MAV_COMP_ID_UART_BRIDGE=241, /* Component to bridge to UART (i.e. from UDP). | */ + MAV_COMP_ID_TUNNEL_NODE=242, /* Component handling TUNNEL messages (e.g. vendor specific GUI of a component). | */ + MAV_COMP_ID_SYSTEM_CONTROL=250, /* Component for handling system messages (e.g. to ARM, takeoff, etc.). | */ MAV_COMPONENT_ENUM_END=251, /* | */ } MAV_COMPONENT; #endif @@ -268,7 +398,12 @@ typedef enum MAV_SYS_STATUS_SENSOR MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */ MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */ MAV_SYS_STATUS_LOGGING=16777216, /* 0x1000000 Logging | */ - MAV_SYS_STATUS_SENSOR_ENUM_END=16777217, /* | */ + MAV_SYS_STATUS_SENSOR_BATTERY=33554432, /* 0x2000000 Battery | */ + MAV_SYS_STATUS_SENSOR_PROXIMITY=67108864, /* 0x4000000 Proximity | */ + MAV_SYS_STATUS_SENSOR_SATCOM=134217728, /* 0x8000000 Satellite Communication | */ + MAV_SYS_STATUS_PREARM_CHECK=268435456, /* 0x10000000 pre-arm check status. Always healthy when armed | */ + MAV_SYS_STATUS_OBSTACLE_AVOIDANCE=536870912, /* 0x20000000 Avoidance/collision prevention | */ + MAV_SYS_STATUS_SENSOR_ENUM_END=536870913, /* | */ } MAV_SYS_STATUS_SENSOR; #endif @@ -277,19 +412,29 @@ typedef enum MAV_SYS_STATUS_SENSOR #define HAVE_ENUM_MAV_FRAME typedef enum MAV_FRAME { - MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ + MAV_FRAME_GLOBAL=0, /* Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). | */ + MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-down (x: North, y: East, z: Down). | */ MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ - MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-up (x: East, y: North, z: Up). | */ + MAV_FRAME_GLOBAL_INT=5, /* Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL). | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */ MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */ MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */ MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_ENUM_END=12, /* | */ + MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ + MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ + MAV_FRAME_BODY_FRD=12, /* Body fixed frame of reference, Z-down (x: Forward, y: Right, z: Down). | */ + MAV_FRAME_RESERVED_13=13, /* MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up). | */ + MAV_FRAME_RESERVED_14=14, /* MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down). | */ + MAV_FRAME_RESERVED_15=15, /* MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up). | */ + MAV_FRAME_RESERVED_16=16, /* MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down). | */ + MAV_FRAME_RESERVED_17=17, /* MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up). | */ + MAV_FRAME_RESERVED_18=18, /* MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down). | */ + MAV_FRAME_RESERVED_19=19, /* MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up). | */ + MAV_FRAME_LOCAL_FRD=20, /* Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). | */ + MAV_FRAME_LOCAL_FLU=21, /* Forward, Left, Up coordinate frame. This is a local frame with Z-up and arbitrary F/L alignment (i.e. not aligned with ENU/earth frame). | */ + MAV_FRAME_ENUM_END=22, /* | */ } MAV_FRAME; #endif @@ -335,7 +480,19 @@ typedef enum FENCE_BREACH } FENCE_BREACH; #endif -/** @brief Enumeration of possible mount operation modes */ +/** @brief Actions being taken to mitigate/prevent fence breach */ +#ifndef HAVE_ENUM_FENCE_MITIGATE +#define HAVE_ENUM_FENCE_MITIGATE +typedef enum FENCE_MITIGATE +{ + FENCE_MITIGATE_UNKNOWN=0, /* Unknown | */ + FENCE_MITIGATE_NONE=1, /* No actions being taken | */ + FENCE_MITIGATE_VEL_LIMIT=2, /* Velocity limiting active to prevent breach | */ + FENCE_MITIGATE_ENUM_END=3, /* | */ +} FENCE_MITIGATE; +#endif + +/** @brief Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages. */ #ifndef HAVE_ENUM_MAV_MOUNT_MODE #define HAVE_ENUM_MAV_MOUNT_MODE typedef enum MAV_MOUNT_MODE @@ -345,131 +502,439 @@ typedef enum MAV_MOUNT_MODE MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ - MAV_MOUNT_MODE_ENUM_END=5, /* | */ + MAV_MOUNT_MODE_SYSID_TARGET=5, /* Gimbal tracks system with specified system ID | */ + MAV_MOUNT_MODE_ENUM_END=6, /* | */ } MAV_MOUNT_MODE; #endif -/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ +/** @brief Gimbal device (low level) capability flags (bitmap) */ +#ifndef HAVE_ENUM_GIMBAL_DEVICE_CAP_FLAGS +#define HAVE_ENUM_GIMBAL_DEVICE_CAP_FLAGS +typedef enum GIMBAL_DEVICE_CAP_FLAGS +{ + GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT=1, /* Gimbal device supports a retracted position | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL=2, /* Gimbal device supports a horizontal, forward looking position, stabilized | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS=4, /* Gimbal device supports rotating around roll axis. | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW=8, /* Gimbal device supports to follow a roll angle relative to the vehicle | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK=16, /* Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized) | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS=32, /* Gimbal device supports rotating around pitch axis. | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW=64, /* Gimbal device supports to follow a pitch angle relative to the vehicle | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK=128, /* Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized) | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS=256, /* Gimbal device supports rotating around yaw axis. | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW=512, /* Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default) | */ + GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK=1024, /* Gimbal device supports locking to an absolute heading (often this is an option available) | */ + GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW=2048, /* Gimbal device supports yawing/panning infinetely (e.g. using slip disk). | */ + GIMBAL_DEVICE_CAP_FLAGS_ENUM_END=2049, /* | */ +} GIMBAL_DEVICE_CAP_FLAGS; +#endif + +/** @brief Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS which are identical with GIMBAL_DEVICE_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags. */ +#ifndef HAVE_ENUM_GIMBAL_MANAGER_CAP_FLAGS +#define HAVE_ENUM_GIMBAL_MANAGER_CAP_FLAGS +typedef enum GIMBAL_MANAGER_CAP_FLAGS +{ + GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT=1, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL=2, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS=4, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW=8, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK=16, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS=32, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW=64, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK=128, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS=256, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW=512, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW. | */ + GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK=1024, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK. | */ + GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW=2048, /* Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW. | */ + GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL=65536, /* Gimbal manager supports to point to a local position. | */ + GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL=131072, /* Gimbal manager supports to point to a global latitude, longitude, altitude position. | */ + GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_FOCAL_LENGTH_SCALE=1048576, /* Gimbal manager supports pitching and yawing at an angular velocity scaled by focal length (the more zoomed in, the slower the movement). | */ + GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_NUDGING=2097152, /* Gimbal manager supports nudging when pointing to a location or tracking. | */ + GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_OVERRIDE=4194304, /* Gimbal manager supports overriding when pointing to a location or tracking. | */ + GIMBAL_MANAGER_CAP_FLAGS_ENUM_END=4194305, /* | */ +} GIMBAL_MANAGER_CAP_FLAGS; +#endif + +/** @brief Flags for gimbal device (lower level) operation. */ +#ifndef HAVE_ENUM_GIMBAL_DEVICE_FLAGS +#define HAVE_ENUM_GIMBAL_DEVICE_FLAGS +typedef enum GIMBAL_DEVICE_FLAGS +{ + GIMBAL_DEVICE_FLAGS_RETRACT=1, /* Set to retracted safe position (no stabilization), takes presedence over all other flags. | */ + GIMBAL_DEVICE_FLAGS_NEUTRAL=2, /* Set to neutral position (horizontal, forward looking, with stabiliziation), takes presedence over all other flags except RETRACT. | */ + GIMBAL_DEVICE_FLAGS_ROLL_LOCK=4, /* Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal. | */ + GIMBAL_DEVICE_FLAGS_PITCH_LOCK=8, /* Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default. | */ + GIMBAL_DEVICE_FLAGS_YAW_LOCK=16, /* Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). | */ + GIMBAL_DEVICE_FLAGS_ENUM_END=17, /* | */ +} GIMBAL_DEVICE_FLAGS; +#endif + +/** @brief Flags for high level gimbal manager operation The first 16 bytes are identical to the GIMBAL_DEVICE_FLAGS. */ +#ifndef HAVE_ENUM_GIMBAL_MANAGER_FLAGS +#define HAVE_ENUM_GIMBAL_MANAGER_FLAGS +typedef enum GIMBAL_MANAGER_FLAGS +{ + GIMBAL_MANAGER_FLAGS_RETRACT=1, /* Based on GIMBAL_DEVICE_FLAGS_RETRACT | */ + GIMBAL_MANAGER_FLAGS_NEUTRAL=2, /* Based on GIMBAL_DEVICE_FLAGS_NEUTRAL | */ + GIMBAL_MANAGER_FLAGS_ROLL_LOCK=4, /* Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK | */ + GIMBAL_MANAGER_FLAGS_PITCH_LOCK=8, /* Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK | */ + GIMBAL_MANAGER_FLAGS_YAW_LOCK=16, /* Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK | */ + GIMBAL_MANAGER_FLAGS_ANGULAR_VELOCITY_RELATIVE_TO_FOCAL_LENGTH=1048576, /* Scale angular velocity relative to focal length. This means the gimbal moves slower if it is zoomed in. | */ + GIMBAL_MANAGER_FLAGS_NUDGE=2097152, /* Interpret attitude control on top of pointing to a location or tracking. If this flag is set, the quaternion is relative to the existing tracking angle. | */ + GIMBAL_MANAGER_FLAGS_OVERRIDE=4194304, /* Completely override pointing to a location or tracking. If this flag is set, the quaternion is (as usual) according to GIMBAL_MANAGER_FLAGS_YAW_LOCK. | */ + GIMBAL_MANAGER_FLAGS_NONE=8388608, /* This flag can be set to give up control previously set using MAV_CMD_DO_GIMBAL_MANAGER_ATTITUDE. This flag must not be combined with other flags. | */ + GIMBAL_MANAGER_FLAGS_ENUM_END=8388609, /* | */ +} GIMBAL_MANAGER_FLAGS; +#endif + +/** @brief Gimbal device (low level) error flags (bitmap, 0 means no error) */ +#ifndef HAVE_ENUM_GIMBAL_DEVICE_ERROR_FLAGS +#define HAVE_ENUM_GIMBAL_DEVICE_ERROR_FLAGS +typedef enum GIMBAL_DEVICE_ERROR_FLAGS +{ + GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT=1, /* Gimbal device is limited by hardware roll limit. | */ + GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT=2, /* Gimbal device is limited by hardware pitch limit. | */ + GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT=4, /* Gimbal device is limited by hardware yaw limit. | */ + GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR=8, /* There is an error with the gimbal encoders. | */ + GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR=16, /* There is an error with the gimbal power source. | */ + GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR=32, /* There is an error with the gimbal motor's. | */ + GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR=64, /* There is an error with the gimbal's software. | */ + GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR=128, /* There is an error with the gimbal's communication. | */ + GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING=256, /* Gimbal is currently calibrating. | */ + GIMBAL_DEVICE_ERROR_FLAGS_ENUM_END=257, /* | */ +} GIMBAL_DEVICE_ERROR_FLAGS; +#endif + +/** @brief Generalized UAVCAN node health */ +#ifndef HAVE_ENUM_UAVCAN_NODE_HEALTH +#define HAVE_ENUM_UAVCAN_NODE_HEALTH +typedef enum UAVCAN_NODE_HEALTH +{ + UAVCAN_NODE_HEALTH_OK=0, /* The node is functioning properly. | */ + UAVCAN_NODE_HEALTH_WARNING=1, /* A critical parameter went out of range or the node has encountered a minor failure. | */ + UAVCAN_NODE_HEALTH_ERROR=2, /* The node has encountered a major failure. | */ + UAVCAN_NODE_HEALTH_CRITICAL=3, /* The node has suffered a fatal malfunction. | */ + UAVCAN_NODE_HEALTH_ENUM_END=4, /* | */ +} UAVCAN_NODE_HEALTH; +#endif + +/** @brief Generalized UAVCAN node mode */ +#ifndef HAVE_ENUM_UAVCAN_NODE_MODE +#define HAVE_ENUM_UAVCAN_NODE_MODE +typedef enum UAVCAN_NODE_MODE +{ + UAVCAN_NODE_MODE_OPERATIONAL=0, /* The node is performing its primary functions. | */ + UAVCAN_NODE_MODE_INITIALIZATION=1, /* The node is initializing; this mode is entered immediately after startup. | */ + UAVCAN_NODE_MODE_MAINTENANCE=2, /* The node is under maintenance. | */ + UAVCAN_NODE_MODE_SOFTWARE_UPDATE=3, /* The node is in the process of updating its software. | */ + UAVCAN_NODE_MODE_OFFLINE=7, /* The node is no longer available online. | */ + UAVCAN_NODE_MODE_ENUM_END=8, /* | */ +} UAVCAN_NODE_MODE; +#endif + +/** @brief Indicates the ESC connection type. */ +#ifndef HAVE_ENUM_ESC_CONNECTION_TYPE +#define HAVE_ENUM_ESC_CONNECTION_TYPE +typedef enum ESC_CONNECTION_TYPE +{ + ESC_CONNECTION_TYPE_PPM=0, /* Traditional PPM ESC. | */ + ESC_CONNECTION_TYPE_SERIAL=1, /* Serial Bus connected ESC. | */ + ESC_CONNECTION_TYPE_ONESHOT=2, /* One Shot PPM ESC. | */ + ESC_CONNECTION_TYPE_I2C=3, /* I2C ESC. | */ + ESC_CONNECTION_TYPE_CAN=4, /* CAN-Bus ESC. | */ + ESC_CONNECTION_TYPE_DSHOT=5, /* DShot ESC. | */ + ESC_CONNECTION_TYPE_ENUM_END=6, /* | */ +} ESC_CONNECTION_TYPE; +#endif + +/** @brief Flags to report ESC failures. */ +#ifndef HAVE_ENUM_ESC_FAILURE_FLAGS +#define HAVE_ENUM_ESC_FAILURE_FLAGS +typedef enum ESC_FAILURE_FLAGS +{ + ESC_FAILURE_NONE=0, /* No ESC failure. | */ + ESC_FAILURE_OVER_CURRENT=1, /* Over current failure. | */ + ESC_FAILURE_OVER_VOLTAGE=2, /* Over voltage failure. | */ + ESC_FAILURE_OVER_TEMPERATURE=4, /* Over temperature failure. | */ + ESC_FAILURE_OVER_RPM=8, /* Over RPM failure. | */ + ESC_FAILURE_INCONSISTENT_CMD=16, /* Inconsistent command failure i.e. out of bounds. | */ + ESC_FAILURE_MOTOR_STUCK=32, /* Motor stuck failure. | */ + ESC_FAILURE_GENERIC=64, /* Generic ESC failure. | */ + ESC_FAILURE_FLAGS_ENUM_END=65, /* | */ +} ESC_FAILURE_FLAGS; +#endif + +/** @brief Flags to indicate the status of camera storage. */ +#ifndef HAVE_ENUM_STORAGE_STATUS +#define HAVE_ENUM_STORAGE_STATUS +typedef enum STORAGE_STATUS +{ + STORAGE_STATUS_EMPTY=0, /* Storage is missing (no microSD card loaded for example.) | */ + STORAGE_STATUS_UNFORMATTED=1, /* Storage present but unformatted. | */ + STORAGE_STATUS_READY=2, /* Storage present and ready. | */ + STORAGE_STATUS_NOT_SUPPORTED=3, /* Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored. | */ + STORAGE_STATUS_ENUM_END=4, /* | */ +} STORAGE_STATUS; +#endif + +/** @brief Yaw behaviour during orbit flight. */ +#ifndef HAVE_ENUM_ORBIT_YAW_BEHAVIOUR +#define HAVE_ENUM_ORBIT_YAW_BEHAVIOUR +typedef enum ORBIT_YAW_BEHAVIOUR +{ + ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER=0, /* Vehicle front points to the center (default). | */ + ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING=1, /* Vehicle front holds heading when message received. | */ + ORBIT_YAW_BEHAVIOUR_UNCONTROLLED=2, /* Yaw uncontrolled. | */ + ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE=3, /* Vehicle front follows flight path (tangential to circle). | */ + ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED=4, /* Yaw controlled by RC input. | */ + ORBIT_YAW_BEHAVIOUR_ENUM_END=5, /* | */ +} ORBIT_YAW_BEHAVIOUR; +#endif + +/** @brief Possible responses from a WIFI_CONFIG_AP message. */ +#ifndef HAVE_ENUM_WIFI_CONFIG_AP_RESPONSE +#define HAVE_ENUM_WIFI_CONFIG_AP_RESPONSE +typedef enum WIFI_CONFIG_AP_RESPONSE +{ + WIFI_CONFIG_AP_RESPONSE_UNDEFINED=0, /* Undefined response. Likely an indicative of a system that doesn't support this request. | */ + WIFI_CONFIG_AP_RESPONSE_ACCEPTED=1, /* Changes accepted. | */ + WIFI_CONFIG_AP_RESPONSE_REJECTED=2, /* Changes rejected. | */ + WIFI_CONFIG_AP_RESPONSE_MODE_ERROR=3, /* Invalid Mode. | */ + WIFI_CONFIG_AP_RESPONSE_SSID_ERROR=4, /* Invalid SSID. | */ + WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR=5, /* Invalid Password. | */ + WIFI_CONFIG_AP_RESPONSE_ENUM_END=6, /* | */ +} WIFI_CONFIG_AP_RESPONSE; +#endif + +/** @brief Possible responses from a CELLULAR_CONFIG message. */ +#ifndef HAVE_ENUM_CELLULAR_CONFIG_RESPONSE +#define HAVE_ENUM_CELLULAR_CONFIG_RESPONSE +typedef enum CELLULAR_CONFIG_RESPONSE +{ + CELLULAR_CONFIG_RESPONSE_ACCEPTED=0, /* Changes accepted. | */ + CELLULAR_CONFIG_RESPONSE_APN_ERROR=1, /* Invalid APN. | */ + CELLULAR_CONFIG_RESPONSE_PIN_ERROR=2, /* Invalid PIN. | */ + CELLULAR_CONFIG_RESPONSE_REJECTED=3, /* Changes rejected. | */ + CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED=4, /* PUK is required to unblock SIM card. | */ + CELLULAR_CONFIG_RESPONSE_ENUM_END=5, /* | */ +} CELLULAR_CONFIG_RESPONSE; +#endif + +/** @brief WiFi Mode. */ +#ifndef HAVE_ENUM_WIFI_CONFIG_AP_MODE +#define HAVE_ENUM_WIFI_CONFIG_AP_MODE +typedef enum WIFI_CONFIG_AP_MODE +{ + WIFI_CONFIG_AP_MODE_UNDEFINED=0, /* WiFi mode is undefined. | */ + WIFI_CONFIG_AP_MODE_AP=1, /* WiFi configured as an access point. | */ + WIFI_CONFIG_AP_MODE_STATION=2, /* WiFi configured as a station connected to an existing local WiFi network. | */ + WIFI_CONFIG_AP_MODE_DISABLED=3, /* WiFi disabled. | */ + WIFI_CONFIG_AP_MODE_ENUM_END=4, /* | */ +} WIFI_CONFIG_AP_MODE; +#endif + +/** @brief Possible values for COMPONENT_INFORMATION.comp_metadata_type. */ +#ifndef HAVE_ENUM_COMP_METADATA_TYPE +#define HAVE_ENUM_COMP_METADATA_TYPE +typedef enum COMP_METADATA_TYPE +{ + COMP_METADATA_TYPE_VERSION=0, /* Version information which also includes information on other optional supported COMP_METADATA_TYPE's. Must be supported. Only downloadable from vehicle. | */ + COMP_METADATA_TYPE_PARAMETER=1, /* Parameter meta data. | */ + COMP_METADATA_TYPE_ENUM_END=2, /* | */ +} COMP_METADATA_TYPE; +#endif + +/** @brief Possible responses from a PARAM_START_TRANSACTION and PARAM_COMMIT_TRANSACTION messages. */ +#ifndef HAVE_ENUM_PARAM_TRANSACTION_RESPONSE +#define HAVE_ENUM_PARAM_TRANSACTION_RESPONSE +typedef enum PARAM_TRANSACTION_RESPONSE +{ + PARAM_TRANSACTION_RESPONSE_ACCEPTED=0, /* Transaction accepted. | */ + PARAM_TRANSACTION_RESPONSE_FAILED=1, /* Transaction failed. | */ + PARAM_TRANSACTION_RESPONSE_UNSUPPORTED=2, /* Transaction unsupported. | */ + PARAM_TRANSACTION_RESPONSE_INPROGRESS=3, /* Transaction in progress. | */ + PARAM_TRANSACTION_RESPONSE_ENUM_END=4, /* | */ +} PARAM_TRANSACTION_RESPONSE; +#endif + +/** @brief Possible transport layers to set and get parameters via mavlink during a parameter transaction. */ +#ifndef HAVE_ENUM_PARAM_TRANSACTION_TRANSPORT +#define HAVE_ENUM_PARAM_TRANSACTION_TRANSPORT +typedef enum PARAM_TRANSACTION_TRANSPORT +{ + PARAM_TRANSACTION_TRANSPORT_PARAM=0, /* Transaction over param transport. | */ + PARAM_TRANSACTION_TRANSPORT_PARAM_EXT=1, /* Transaction over param_ext transport. | */ + PARAM_TRANSACTION_TRANSPORT_ENUM_END=2, /* | */ +} PARAM_TRANSACTION_TRANSPORT; +#endif + +/** @brief Possible parameter transaction action during a commit. */ +#ifndef HAVE_ENUM_PARAM_TRANSACTION_ACTION +#define HAVE_ENUM_PARAM_TRANSACTION_ACTION +typedef enum PARAM_TRANSACTION_ACTION +{ + PARAM_TRANSACTION_ACTION_COMMIT=0, /* Commit the current parameter transaction. | */ + PARAM_TRANSACTION_ACTION_CANCEL=1, /* Cancel the current parameter transaction. | */ + PARAM_TRANSACTION_ACTION_ENUM_END=2, /* | */ +} PARAM_TRANSACTION_ACTION; +#endif + +/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries */ #ifndef HAVE_ENUM_MAV_CMD #define HAVE_ENUM_MAV_CMD typedef enum MAV_CMD { - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. |Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)| 0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Number of turns.| Leave loiter circle only once heading towards the next waypoint (0 = False)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. |Loiter time (only starts once Lat, Lon and Alt is reached).| Leave loiter circle only once heading towards the next waypoint (0 = False)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */ MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Abort Alt| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ - MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ - MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. | Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ - MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_FOLLOW=32, /* Being following a target |System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode| RESERVED| RESERVED| altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home| altitude| RESERVED| TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout| */ - MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target (m)| X offset from target (m)| Y offset from target (m)| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LAND=21, /* Land at location. |Minimum target altitude if landing is aborted (0 = undefined/use system default).| Precision land mode.| Empty| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude.| Longitude.| Landing altitude (ground level in current frame).| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode. |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate| Desired yaw angle| Y-axis position| X-axis position| Z-axis / ground level position| */ + MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Takeoff ascend rate| Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position| X-axis position| Z-axis position| */ + MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around waypoint. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude.| Empty| Empty| Empty| Empty| Empty| Desired altitude| */ + MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Leave loiter circle only once heading towards the next waypoint (0 = False)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_FOLLOW=32, /* Begin following a target |System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.| Reserved| Reserved| Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.| Altitude above home. (used if mode=2)| Reserved| Time to land in which the MAV should go to the default position hold mode after a message RX timeout.| */ + MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target| X offset from target| Y offset from target| */ + MAV_CMD_DO_ORBIT=34, /* Start orbiting on the circumference of a circle defined by the parameters. Setting any value NaN results in using defaults. |Radius of the circle. positive: Orbit clockwise. negative: Orbit counter-clockwise.| Tangential Velocity. NaN: Vehicle configuration default.| Yaw behavior of the vehicle.| Reserved (e.g. for dynamic center beacon options)| Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.| Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.| Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode.| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to waypoint using a spline path. |Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.). |Empty| Front transition heading.| Empty| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Approach altitude (with the same reference as the Altitude field). NaN if unspecified.| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude (ground level)| */ MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */ + MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay (-1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */ + MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload. |Maximum distance to descend.| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate.| Empty| Empty| Empty| Empty| Empty| Target Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance.| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle, 0 is north| angular speed| direction: -1: counter clockwise, 1: clockwise| 0: absolute angle, 1: relative offset| Empty| Empty| Empty| */ MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| absolute or relative [0,1]| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)| Speed (-1 indicates no change)| Throttle (-1 indicates no change)| 0: absolute, 1: relative| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Yaw angle. NaN to use default heading| Latitude| Longitude| Altitude| */ MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay instance number.| Setting. (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cycles with a desired period. |Relay instance number.| Cycle count.| Cycle time.| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo instance number.| Pulse Width Modulation.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo instance number.| Pulse Width Modulation.| Cycle count.| Cycle time.| Empty| Empty| Empty| */ MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_ALTITUDE=186, /* Change altitude set point. |Altitude in meters| Mav frame of new altitude (see MAV_FRAME)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ - MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. |Ground speed, less than 0 (-1) for default| Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum.| Reserved| Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */ + MAV_CMD_DO_CHANGE_ALTITUDE=186, /* Change altitude set point. |Altitude| Frame of new altitude.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ACTUATOR=187, /* Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter). |Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.| Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7)| */ + MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ + MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude| Landing speed| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonomous landing. |Altitude| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. |Ground speed, less than 0 (-1) for default| Bitmask of option flags.| Reserved| Yaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude| Longitude| Altitude| */ MAV_CMD_DO_PAUSE_CONTINUE=193, /* If in a GPS controlled position mode, hold the current position or continue. |0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ MAV_CMD_DO_SET_REVERSE=194, /* Set moving direction to forward or reverse. |Direction (0=Forward, 1=Reverse)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch (WIP: DEPRECATED: or lat in degrees) depending on mount mode.| roll (WIP: DEPRECATED: or lon in degrees) depending on mount mode.| yaw (WIP: DEPRECATED: or alt in meters) depending on mount mode.| WIP: alt in meters depending on mount mode.| WIP: latitude in degrees * 1E7, set if appropriate mount mode.| WIP: longitude in degrees * 1E7, set if appropriate mount mode.| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI_LOCATION=195, /* Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. (Send command multiple times for more than one but not all gimbals.)| Empty| Empty| Empty| Latitude of ROI location| Longitude of ROI location| Altitude of ROI location| */ + MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET=196, /* Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. (Send command multiple times for more than one but not all gimbals.)| Empty| Empty| Empty| Pitch offset from next waypoint, positive tilting up| roll offset from next waypoint, positive banking to the right| yaw offset from next waypoint, positive panning to the right| */ + MAV_CMD_DO_SET_ROI_NONE=197, /* Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. (Send command multiple times for more than one but not all gimbals.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI_SYSID=198, /* Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. |System ID| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. (Send command multiple times for more than one but not all gimbals.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode.| Waypoint index/ target ID (depends on param 1).| Region of interest index. (allows a vehicle to manage multiple ROI's)| Empty| MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude| MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude| MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). |Modes: P, TV, AV, M, Etc.| Shutter speed: Divisor number for one second.| Aperture: F stop number.| ISO number e.g. 80, 100, 200, Etc.| Exposure type enumerator.| Command Identity.| Main engine cut-off time before camera trigger. (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch depending on mount mode (degrees or degrees/second depending on pitch input).| roll depending on mount mode (degrees or degrees/second depending on roll input).| yaw depending on mount mode (degrees or degrees/second depending on yaw input).| altitude depending on mount mode.| latitude, set if appropriate mount mode.| longitude, set if appropriate mount mode.| Mount mode.| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. |Camera trigger distance. 0 to stop triggering.| Camera shutter integration time. -1 or 0 to ignore| Trigger camera once immediately. (0 = no trigger, 1 = trigger)| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_SET_YAW_SPEED=213, /* Sets a desired vehicle turn angle and speed change |yaw angle to adjust steering by in centidegress| speed - normalized to 0 .. 1| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ + MAV_CMD_DO_PARACHUTE=208, /* Mission item/command to release a parachute or enable/disable auto release. |Action| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test. |Motor instance number. (from 1 to max number of motors on the vehicle)| Throttle type.| Throttle.| Timeout.| Motor count. (number of motors to test to test in sequence, waiting for the timeout above between them; 0=1 motor, 1=1 motor, 2=2 motors...)| Motor test order.| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight. |Inverted flight. (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_SET_YAW_SPEED=213, /* Sets a desired vehicle turn angle and speed change. |Yaw angle to adjust steering by.| Speed.| Final angle. (0=absolute, 1=relative)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL=214, /* Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. |Camera trigger cycle time. -1 or 0 to ignore.| Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |quaternion param q1, w (1 in null-rotation)| quaternion param q2, x (0 in null-rotation)| quaternion param q3, y (0 in null-rotation)| quaternion param q4, z (0 in null-rotation)| Empty| Empty| Empty| */ MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ - MAV_CMD_DO_ENGINE_CONTROL=223, /* Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |0: Stop engine, 1:Start Engine| 0: Warm start, 1:Cold start. Controls use of choke where applicable| Height delay (meters). This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_LIMITS=222, /* Set limits for external control |Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.| Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.| Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.| Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.| Empty| Empty| Empty| */ + MAV_CMD_DO_ENGINE_CONTROL=223, /* Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |0: Stop engine, 1:Start Engine| 0: Warm start, 1:Cold start. Controls use of choke where applicable| Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MISSION_CURRENT=224, /* Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). |Mission sequence value to set| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. |1: gyro calibration, 3: gyro temperature calibration| 1: magnetometer calibration| 1: ground pressure calibration| 1: radio RC calibration, 2: RC trim calibration| 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration| 1: APM: compass/motor interference calibration / PX4: airspeed calibration| 1: ESC calibration, 3: barometer temperature calibration| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. |1: gyro calibration, 3: gyro temperature calibration| 1: magnetometer calibration| 1: ground pressure calibration| 1: radio RC calibration, 2: RC trim calibration| 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration| 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration| 1: ESC calibration, 3: barometer temperature calibration| */ MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.| WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded| WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded| Reserved, send 0| Reserved, send 0| WIP: ID (e.g. camera ID -1 for all IDs)| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: logging rate (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.| WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded| WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded| Reserved (set to 0)| Reserved (set to 0)| WIP: ID (e.g. camera ID -1 for all IDs)| */ + MAV_CMD_DO_UPGRADE=247, /* Request a target system to start an upgrade of one (or all) of its components. For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller. The system doing the upgrade will report progress using the normal command protocol sequence for a long running operation. Command protocol information: https://mavlink.io/en/services/command.html. |Component id of the component to be upgraded. If set to 0, all components should be upgraded.| 0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed.| Reserved| Reserved| Reserved| Reserved| WIP: upgrade progress report rate (can be used for more granular control).| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position. |MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.| MAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position.| Coordinate frame of hold point.| Desired yaw angle.| Latitude/X position.| Longitude/Y position.| Altitude/Z position.| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |0: disarm, 1: arm| 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ILLUMINATOR_ON_OFF=405, /* Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). |0: Illuminators OFF, 1: Illuminators ON| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ - MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ - MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_CAMERA_INFORMATION=521, /* WIP: Request camera information (CAMERA_INFORMATION) |1: Request camera capabilities| Camera ID| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_CAMERA_SETTINGS=522, /* WIP: Request camera settings (CAMERA_SETTINGS) |1: Request camera settings| Camera ID| Reserved (all remaining params)| */ - MAV_CMD_SET_CAMERA_SETTINGS_1=523, /* WIP: Set the camera settings part 1 (CAMERA_SETTINGS) |Camera ID| Aperture (1/value)| Aperture locked (0: auto, 1: locked)| Shutter speed in s| Shutter speed locked (0: auto, 1: locked)| ISO sensitivity| ISO sensitivity locked (0: auto, 1: locked)| */ - MAV_CMD_SET_CAMERA_SETTINGS_2=524, /* WIP: Set the camera settings part 2 (CAMERA_SETTINGS) |Camera ID| White balance locked (0: auto, 1: locked)| White balance (color temperature in K)| Reserved for camera mode ID| Reserved for color mode ID| Reserved for image format ID| Reserved| */ - MAV_CMD_REQUEST_STORAGE_INFORMATION=525, /* WIP: Request storage information (STORAGE_INFORMATION) |1: Request storage information| Storage ID| Reserved (all remaining params)| */ - MAV_CMD_STORAGE_FORMAT=526, /* WIP: Format a storage medium |1: Format storage| Storage ID| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS=527, /* WIP: Request camera capture status (CAMERA_CAPTURE_STATUS) |1: Request camera capture status| Camera ID| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_FLIGHT_INFORMATION=528, /* WIP: Request flight information (FLIGHT_INFORMATION) |1: Request flight information| Reserved (all remaining params)| */ - MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc), set to 0 if param 4/5 are used, set to -1 for highest resolution possible.| WIP: Resolution horizontal in pixels| WIP: Resolution horizontal in pixels| WIP: Camera ID| */ - MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Camera ID| Reserved| */ - MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ - MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture (recording) |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second, set to -1 for highest framerate possible.| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc), set to 0 if param 4/5 are used, set to -1 for highest resolution possible.| WIP: Resolution horizontal in pixels| WIP: Resolution horizontal in pixels| WIP: Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz)| */ - MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture (recording) |WIP: Camera ID| Reserved| */ + MAV_CMD_INJECT_FAILURE=420, /* Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting. |The unit which is affected by the failure.| The type how the failure manifests itself.| Instance affected by failure (0 to signal all).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing. |0:Spektrum.| RC type.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message. |The MAVLink message ID| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. |The MAVLink message ID| The interval between two messages. Set to -1 to disable and 0 to request default rate.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast.| */ + MAV_CMD_REQUEST_MESSAGE=512, /* Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL). |The MAVLink message ID of the requested message.| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requestor, 2: broadcast.| */ + MAV_CMD_REQUEST_PROTOCOL_VERSION=519, /* Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message |1: Request supported protocol versions by all nodes on the network| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message |1: Request autopilot version| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_CAMERA_INFORMATION=521, /* Request camera information (CAMERA_INFORMATION). |0: No action 1: Request camera capabilities| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_CAMERA_SETTINGS=522, /* Request camera settings (CAMERA_SETTINGS). |0: No Action 1: Request camera settings| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_STORAGE_INFORMATION=525, /* Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage. |Storage ID (0 for all, 1 for first, 2 for second, etc.)| 0: No Action 1: Request storage information| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_STORAGE_FORMAT=526, /* Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage. |Storage ID (1 for first, 2 for second, etc.)| Format storage (and reset image log). 0: No action 1: Format storage| Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. 0: No action 1: Reset Image Log| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS=527, /* Request camera capture status (CAMERA_CAPTURE_STATUS) |0: No Action 1: Request camera capture status| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_FLIGHT_INFORMATION=528, /* Request flight information (FLIGHT_INFORMATION) |1: Request flight information| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_RESET_CAMERA_SETTINGS=529, /* Reset all camera settings to Factory Default |0: No Action 1: Reset all settings| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_SET_CAMERA_MODE=530, /* Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming. |Reserved (Set to 0)| Camera mode| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */ + MAV_CMD_SET_CAMERA_ZOOM=531, /* Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). |Zoom type| Zoom value. The range of valid values depend on the zoom type.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */ + MAV_CMD_SET_CAMERA_FOCUS=532, /* Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). |Focus type| Focus value| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */ + MAV_CMD_JUMP_TAG=600, /* Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. |Tag.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_DO_JUMP_TAG=601, /* Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. |Target tag to jump to.| Repeat count.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_DO_GIMBAL_MANAGER_TILTPAN=1000, /* High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. |Tilt/pitch rate (positive to tilt up).| Pan/yaw rate (positive to pan to the right).| Tilt/pitch angle (positive to tilt up, relative to vehicle for PAN mode, relative to world horizon for HOLD mode).| Pan/yaw angle (positive to pan to the right, relative to vehicle for PAN mode, absolute to North for HOLD mode).| Gimbal manager flags to use.| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. (Send command multiple times for more than one but not all gimbals.)| */ + MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. |Reserved (Set to 0)| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1). Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted. Use 0 to ignore it.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence Use NaN for reserved values. |Reserved (Set to 0)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */ + MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE=2002, /* Re-request a CAMERA_IMAGE_CAPTURED message. |Sequence number for missing CAMERA_IMAGE_CAPTURED message| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */ + MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start), -1 to ignore| 1 to reset the trigger sequence, -1 or 0 to ignore| 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_CAMERA_TRACK_POINT=2004, /* If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking. |Point to track x value (normalized 0..1, 0 is left, 1 is right).| Point to track y value (normalized 0..1, 0 is top, 1 is bottom).| Point radius (normalized 0..1, 0 is image left, 1 is image right).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_CAMERA_TRACK_RECTANGLE=2005, /* If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking. |Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_CAMERA_STOP_TRACKING=2010, /* Stops ongoing tracking. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture (recording). |Video Stream ID (0 for all streams)| Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| */ + MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture (recording). |Video Stream ID (0 for all streams)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| */ + MAV_CMD_VIDEO_START_STREAMING=2502, /* Start video streaming |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_VIDEO_STOP_STREAMING=2503, /* Stop the given video stream |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION=2504, /* Request video stream information (VIDEO_STREAM_INFORMATION) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_REQUEST_VIDEO_STREAM_STATUS=2505, /* Request video stream status (VIDEO_STREAM_STATUS) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ MAV_CMD_LOGGING_START=2510, /* Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) |Format: 0: ULog| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */ MAV_CMD_LOGGING_STOP=2511, /* Request to stop streaming log data over MAVLink |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */ - MAV_CMD_AIRFRAME_CONFIGURATION=2520, /* |Landing gear ID (default: 0, -1 for all)| Landing gear position (Down: 0, Up: 1, NAN for no change)| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| */ - MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ - MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ - MAV_CMD_SET_GUIDED_SUBMODE_STANDARD=4000, /* This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocites along all three axes. - | */ + MAV_CMD_AIRFRAME_CONFIGURATION=2520, /* |Landing gear ID (default: 0, -1 for all)| Landing gear position (Down: 0, Up: 1, NaN for no change)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| */ + MAV_CMD_CONTROL_HIGH_LATENCY=2600, /* Request to start/stop transmitting over the high latency telemetry |Control transmission over high latency telemetry (0: stop, 1: start)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (+- 0.5 the total angle)| Viewing angle vertical of panorama.| Speed of the horizontal rotation.| Speed of the vertical rotation.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ARM_AUTHORIZATION_REQUEST=3001, /* Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the progress of command_ack message should be set with period of time that this authorization is valid in seconds or in case it was denied it should be set with one of the reasons in ARM_AUTH_DENIED_REASON. + |Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_SET_GUIDED_SUBMODE_STANDARD=4000, /* This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes. + |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE=4001, /* This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position. - |Radius of desired circle in CIRCLE_MODE| User defined| User defined| User defined| Unscaled target latitude of center of circle in CIRCLE_MODE| Unscaled target longitude of center of circle in CIRCLE_MODE| */ + |Radius of desired circle in CIRCLE_MODE| User defined| User defined| User defined| Target latitude of center of circle in CIRCLE_MODE| Target longitude of center of circle in CIRCLE_MODE| Reserved (default:0)| */ + MAV_CMD_CONDITION_GATE=4501, /* Delay mission state machine until gate has been reached. |Geometry: 0: orthogonal to path between previous and next waypoint.| Altitude: 0: ignore altitude| Empty| Empty| Latitude| Longitude| Altitude| */ MAV_CMD_NAV_FENCE_RETURN_POINT=5000, /* Fence return point. There can only be one fence return point. |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION=5001, /* Fence vertex for an inclusion polygon. The vehicle must stay within this area. Minimum of 3 vertices required. + MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION=5001, /* Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. |Polygon vertex count| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */ - MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION=5002, /* Fence vertex for an exclusion polygon. The vehicle must stay outside this area. Minimum of 3 vertices required. + MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION=5002, /* Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. |Polygon vertex count| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */ + MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION=5003, /* Circular fence area. The vehicle must stay inside this area. + |Radius.| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */ + MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION=5004, /* Circular fence area. The vehicle must stay outside this area. + |Radius.| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */ MAV_CMD_NAV_RALLY_POINT=5100, /* Rally point. You can have multiple rally points defined. |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */ - MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ - MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_UAVCAN_GET_NODE_INFO=5200, /* Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages. |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */ + MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will.| Latitude. Note, if used in MISSION_ITEM (deprecated) the units are degrees (unscaled)| Longitude. Note, if used in MISSION_ITEM (deprecated) the units are degrees (unscaled)| Altitude (MSL)| */ + MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ + MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */ MAV_CMD_USER_1=31010, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ MAV_CMD_USER_2=31011, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ MAV_CMD_USER_3=31012, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ @@ -479,7 +944,7 @@ typedef enum MAV_CMD } MAV_CMD; #endif -/** @brief THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a +/** @brief A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */ #ifndef HAVE_ENUM_MAV_DATA_STREAM @@ -499,7 +964,7 @@ typedef enum MAV_DATA_STREAM } MAV_DATA_STREAM; #endif -/** @brief The ROI (region of interest) for the vehicle. This can be +/** @brief The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI). */ #ifndef HAVE_ENUM_MAV_ROI @@ -507,8 +972,8 @@ typedef enum MAV_DATA_STREAM typedef enum MAV_ROI { MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ - MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ + MAV_ROI_WPNEXT=1, /* Point toward next waypoint, with optional pitch/roll/yaw offset. | */ + MAV_ROI_WPINDEX=2, /* Point toward given waypoint. | */ MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ MAV_ROI_TARGET=4, /* Point toward of given id. | */ MAV_ROI_ENUM_END=5, /* | */ @@ -520,15 +985,15 @@ typedef enum MAV_ROI #define HAVE_ENUM_MAV_CMD_ACK typedef enum MAV_CMD_ACK { - MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ - MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ - MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ - MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ - MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ - MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ - MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ - MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ - MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ + MAV_CMD_ACK_OK=1, /* Command / mission item is ok. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ + MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */ MAV_CMD_ACK_ENUM_END=10, /* | */ } MAV_CMD_ACK; #endif @@ -552,41 +1017,64 @@ typedef enum MAV_PARAM_TYPE } MAV_PARAM_TYPE; #endif -/** @brief result from a mavlink command */ +/** @brief Specifies the datatype of a MAVLink extended parameter. */ +#ifndef HAVE_ENUM_MAV_PARAM_EXT_TYPE +#define HAVE_ENUM_MAV_PARAM_EXT_TYPE +typedef enum MAV_PARAM_EXT_TYPE +{ + MAV_PARAM_EXT_TYPE_UINT8=1, /* 8-bit unsigned integer | */ + MAV_PARAM_EXT_TYPE_INT8=2, /* 8-bit signed integer | */ + MAV_PARAM_EXT_TYPE_UINT16=3, /* 16-bit unsigned integer | */ + MAV_PARAM_EXT_TYPE_INT16=4, /* 16-bit signed integer | */ + MAV_PARAM_EXT_TYPE_UINT32=5, /* 32-bit unsigned integer | */ + MAV_PARAM_EXT_TYPE_INT32=6, /* 32-bit signed integer | */ + MAV_PARAM_EXT_TYPE_UINT64=7, /* 64-bit unsigned integer | */ + MAV_PARAM_EXT_TYPE_INT64=8, /* 64-bit signed integer | */ + MAV_PARAM_EXT_TYPE_REAL32=9, /* 32-bit floating-point | */ + MAV_PARAM_EXT_TYPE_REAL64=10, /* 64-bit floating-point | */ + MAV_PARAM_EXT_TYPE_CUSTOM=11, /* Custom Type | */ + MAV_PARAM_EXT_TYPE_ENUM_END=12, /* | */ +} MAV_PARAM_EXT_TYPE; +#endif + +/** @brief Result from a MAVLink command (MAV_CMD) */ #ifndef HAVE_ENUM_MAV_RESULT #define HAVE_ENUM_MAV_RESULT typedef enum MAV_RESULT { - MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ - MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ - MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ - MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ - MAV_RESULT_FAILED=4, /* Command executed, but failed | */ - MAV_RESULT_ENUM_END=5, /* | */ + MAV_RESULT_ACCEPTED=0, /* Command is valid (is supported and has valid parameters), and was executed. | */ + MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work. | */ + MAV_RESULT_DENIED=2, /* Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work. | */ + MAV_RESULT_UNSUPPORTED=3, /* Command is not supported (unknown). | */ + MAV_RESULT_FAILED=4, /* Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc. | */ + MAV_RESULT_IN_PROGRESS=5, /* Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. | */ + MAV_RESULT_CANCELLED=6, /* Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). | */ + MAV_RESULT_ENUM_END=7, /* | */ } MAV_RESULT; #endif -/** @brief result in a mavlink mission ack */ +/** @brief Result of mission operation (in a MISSION_ACK message). */ #ifndef HAVE_ENUM_MAV_MISSION_RESULT #define HAVE_ENUM_MAV_MISSION_RESULT typedef enum MAV_MISSION_RESULT { MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ - MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ - MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ - MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ - MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ - MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ - MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ - MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ - MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ - MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ - MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ - MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ - MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ - MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ - MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ - MAV_MISSION_RESULT_ENUM_END=15, /* | */ + MAV_MISSION_ERROR=1, /* Generic error / not accepting mission commands at all right now. | */ + MAV_MISSION_UNSUPPORTED_FRAME=2, /* Coordinate frame is not supported. | */ + MAV_MISSION_UNSUPPORTED=3, /* Command is not supported. | */ + MAV_MISSION_NO_SPACE=4, /* Mission items exceed storage space. | */ + MAV_MISSION_INVALID=5, /* One of the parameters has an invalid value. | */ + MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value. | */ + MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value. | */ + MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value. | */ + MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value. | */ + MAV_MISSION_INVALID_PARAM5_X=10, /* x / param5 has an invalid value. | */ + MAV_MISSION_INVALID_PARAM6_Y=11, /* y / param6 has an invalid value. | */ + MAV_MISSION_INVALID_PARAM7=12, /* z / param7 has an invalid value. | */ + MAV_MISSION_INVALID_SEQUENCE=13, /* Mission item received out of sequence | */ + MAV_MISSION_DENIED=14, /* Not accepting any mission commands from this communication partner. | */ + MAV_MISSION_OPERATION_CANCELLED=15, /* Current mission operation cancelled (e.g. mission upload, mission download). | */ + MAV_MISSION_RESULT_ENUM_END=16, /* | */ } MAV_MISSION_RESULT; #endif @@ -600,7 +1088,7 @@ typedef enum MAV_SEVERITY MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ - MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ + MAV_SEVERITY_NOTICE=5, /* An unusual event has occurred, though not an error condition. This should be investigated for the root cause. | */ MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ MAV_SEVERITY_ENUM_END=8, /* | */ @@ -632,7 +1120,17 @@ typedef enum SERIAL_CONTROL_DEV SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */ - SERIAL_CONTROL_DEV_ENUM_END=11, /* | */ + SERIAL_CONTROL_SERIAL0=100, /* SERIAL0 | */ + SERIAL_CONTROL_SERIAL1=101, /* SERIAL1 | */ + SERIAL_CONTROL_SERIAL2=102, /* SERIAL2 | */ + SERIAL_CONTROL_SERIAL3=103, /* SERIAL3 | */ + SERIAL_CONTROL_SERIAL4=104, /* SERIAL4 | */ + SERIAL_CONTROL_SERIAL5=105, /* SERIAL5 | */ + SERIAL_CONTROL_SERIAL6=106, /* SERIAL6 | */ + SERIAL_CONTROL_SERIAL7=107, /* SERIAL7 | */ + SERIAL_CONTROL_SERIAL8=108, /* SERIAL8 | */ + SERIAL_CONTROL_SERIAL9=109, /* SERIAL9 | */ + SERIAL_CONTROL_DEV_ENUM_END=110, /* | */ } SERIAL_CONTROL_DEV; #endif @@ -658,7 +1156,9 @@ typedef enum MAV_DISTANCE_SENSOR MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */ MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */ MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */ - MAV_DISTANCE_SENSOR_ENUM_END=3, /* | */ + MAV_DISTANCE_SENSOR_RADAR=3, /* Radar type, e.g. uLanding units | */ + MAV_DISTANCE_SENSOR_UNKNOWN=4, /* Broken or unknown type, e.g. analog units | */ + MAV_DISTANCE_SENSOR_ENUM_END=5, /* | */ } MAV_DISTANCE_SENSOR; #endif @@ -705,8 +1205,12 @@ typedef enum MAV_SENSOR_ORIENTATION MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */ MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */ MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315=38, /* Roll: 315, Pitch: 315, Yaw: 315 | */ - MAV_SENSOR_ORIENTATION_ENUM_END=39, /* | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293=38, /* Roll: 90, Pitch: 68, Yaw: 293 | */ + MAV_SENSOR_ROTATION_PITCH_315=39, /* Pitch: 315 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_315=40, /* Roll: 90, Pitch: 315 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_180=41, /* Roll: 270, Yaw: 180 | */ + MAV_SENSOR_ROTATION_CUSTOM=100, /* Custom orientation | */ + MAV_SENSOR_ORIENTATION_ENUM_END=101, /* | */ } MAV_SENSOR_ORIENTATION; #endif @@ -717,7 +1221,7 @@ typedef enum MAV_PROTOCOL_CAPABILITY { MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */ MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */ + MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_ITEM_INT scaled integer message type. | */ MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */ MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */ MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. | */ @@ -728,10 +1232,11 @@ typedef enum MAV_PROTOCOL_CAPABILITY MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET=1024, /* Autopilot supports direct actuator control. | */ MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the flight termination command. | */ MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */ - MAV_PROTOCOL_CAPABILITY_MAVLINK2=8192, /* Autopilot supports mavlink version 2. | */ + MAV_PROTOCOL_CAPABILITY_MAVLINK2=8192, /* Autopilot supports MAVLink version 2. | */ MAV_PROTOCOL_CAPABILITY_MISSION_FENCE=16384, /* Autopilot supports mission fence protocol. | */ MAV_PROTOCOL_CAPABILITY_MISSION_RALLY=32768, /* Autopilot supports mission rally point protocol. | */ - MAV_PROTOCOL_CAPABILITY_ENUM_END=32769, /* | */ + MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION=65536, /* Autopilot supports the flight information protocol. | */ + MAV_PROTOCOL_CAPABILITY_ENUM_END=65537, /* | */ } MAV_PROTOCOL_CAPABILITY; #endif @@ -741,8 +1246,8 @@ typedef enum MAV_PROTOCOL_CAPABILITY typedef enum MAV_MISSION_TYPE { MAV_MISSION_TYPE_MISSION=0, /* Items are mission commands for main mission. | */ - MAV_MISSION_TYPE_FENCE=1, /* Specifies GeoFence area(s). Items are MAV_CMD_FENCE_ GeoFence items. | */ - MAV_MISSION_TYPE_RALLY=2, /* Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_RALLY_POINT rally point items. | */ + MAV_MISSION_TYPE_FENCE=1, /* Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items. | */ + MAV_MISSION_TYPE_RALLY=2, /* Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items. | */ MAV_MISSION_TYPE_ALL=255, /* Only used in MISSION_CLEAR_ALL to clear all mission types. | */ MAV_MISSION_TYPE_ENUM_END=256, /* | */ } MAV_MISSION_TYPE; @@ -753,12 +1258,16 @@ typedef enum MAV_MISSION_TYPE #define HAVE_ENUM_MAV_ESTIMATOR_TYPE typedef enum MAV_ESTIMATOR_TYPE { + MAV_ESTIMATOR_TYPE_UNKNOWN=0, /* Unknown type of the estimator. | */ MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */ MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */ MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */ MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */ MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */ - MAV_ESTIMATOR_TYPE_ENUM_END=6, /* | */ + MAV_ESTIMATOR_TYPE_MOCAP=6, /* Estimate from external motion capturing system. | */ + MAV_ESTIMATOR_TYPE_LIDAR=7, /* Estimator based on lidar sensor input. | */ + MAV_ESTIMATOR_TYPE_AUTOPILOT=8, /* Estimator on autopilot. | */ + MAV_ESTIMATOR_TYPE_ENUM_END=9, /* | */ } MAV_ESTIMATOR_TYPE; #endif @@ -790,6 +1299,70 @@ typedef enum MAV_BATTERY_FUNCTION } MAV_BATTERY_FUNCTION; #endif +/** @brief Enumeration for battery charge states. */ +#ifndef HAVE_ENUM_MAV_BATTERY_CHARGE_STATE +#define HAVE_ENUM_MAV_BATTERY_CHARGE_STATE +typedef enum MAV_BATTERY_CHARGE_STATE +{ + MAV_BATTERY_CHARGE_STATE_UNDEFINED=0, /* Low battery state is not provided | */ + MAV_BATTERY_CHARGE_STATE_OK=1, /* Battery is not in low state. Normal operation. | */ + MAV_BATTERY_CHARGE_STATE_LOW=2, /* Battery state is low, warn and monitor close. | */ + MAV_BATTERY_CHARGE_STATE_CRITICAL=3, /* Battery state is critical, return or abort immediately. | */ + MAV_BATTERY_CHARGE_STATE_EMERGENCY=4, /* Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage. | */ + MAV_BATTERY_CHARGE_STATE_FAILED=5, /* Battery failed, damage unavoidable. | */ + MAV_BATTERY_CHARGE_STATE_UNHEALTHY=6, /* Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. | */ + MAV_BATTERY_CHARGE_STATE_CHARGING=7, /* Battery is charging. | */ + MAV_BATTERY_CHARGE_STATE_ENUM_END=8, /* | */ +} MAV_BATTERY_CHARGE_STATE; +#endif + +/** @brief Smart battery supply status/fault flags (bitmask) for health indication. */ +#ifndef HAVE_ENUM_MAV_SMART_BATTERY_FAULT +#define HAVE_ENUM_MAV_SMART_BATTERY_FAULT +typedef enum MAV_SMART_BATTERY_FAULT +{ + MAV_SMART_BATTERY_FAULT_DEEP_DISCHARGE=1, /* Battery has deep discharged. | */ + MAV_SMART_BATTERY_FAULT_SPIKES=2, /* Voltage spikes. | */ + MAV_SMART_BATTERY_FAULT_SINGLE_CELL_FAIL=4, /* Single cell has failed. | */ + MAV_SMART_BATTERY_FAULT_OVER_CURRENT=8, /* Over-current fault. | */ + MAV_SMART_BATTERY_FAULT_OVER_TEMPERATURE=16, /* Over-temperature fault. | */ + MAV_SMART_BATTERY_FAULT_UNDER_TEMPERATURE=32, /* Under-temperature fault. | */ + MAV_SMART_BATTERY_FAULT_ENUM_END=33, /* | */ +} MAV_SMART_BATTERY_FAULT; +#endif + +/** @brief Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly). */ +#ifndef HAVE_ENUM_MAV_GENERATOR_STATUS_FLAG +#define HAVE_ENUM_MAV_GENERATOR_STATUS_FLAG +typedef enum MAV_GENERATOR_STATUS_FLAG +{ + MAV_GENERATOR_STATUS_FLAG_OFF=1, /* Generator is off. | */ + MAV_GENERATOR_STATUS_FLAG_READY=2, /* Generator is ready to start generating power. | */ + MAV_GENERATOR_STATUS_FLAG_GENERATING=4, /* Generator is generating power. | */ + MAV_GENERATOR_STATUS_FLAG_CHARGING=8, /* Generator is charging the batteries (generating enough power to charge and provide the load). | */ + MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER=16, /* Generator is operating at a reduced maximum power. | */ + MAV_GENERATOR_STATUS_FLAG_MAXPOWER=32, /* Generator is providing the maximum output. | */ + MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING=64, /* Generator is near the maximum operating temperature, cooling is insufficient. | */ + MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT=128, /* Generator hit the maximum operating temperature and shutdown. | */ + MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING=256, /* Power electronics are near the maximum operating temperature, cooling is insufficient. | */ + MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT=512, /* Power electronics hit the maximum operating temperature and shutdown. | */ + MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT=1024, /* Power electronics experienced a fault and shutdown. | */ + MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT=2048, /* The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening. | */ + MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING=4096, /* Generator controller having communication problems. | */ + MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING=8192, /* Power electronic or generator cooling system error. | */ + MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT=16384, /* Generator controller power rail experienced a fault. | */ + MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT=32768, /* Generator controller exceeded the overcurrent threshold and shutdown to prevent damage. | */ + MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT=65536, /* Generator controller detected a high current going into the batteries and shutdown to prevent battery damage. | */ + MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT=131072, /* Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating. | */ + MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT=262144, /* Batteries are under voltage (generator will not start). | */ + MAV_GENERATOR_STATUS_FLAG_START_INHIBITED=524288, /* Generator start is inhibited by e.g. a safety switch. | */ + MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED=1048576, /* Generator requires maintenance. | */ + MAV_GENERATOR_STATUS_FLAG_WARMING_UP=2097152, /* Generator is not ready to generate yet. | */ + MAV_GENERATOR_STATUS_FLAG_IDLE=4194304, /* Generator is idle. | */ + MAV_GENERATOR_STATUS_FLAG_ENUM_END=4194305, /* | */ +} MAV_GENERATOR_STATUS_FLAG; +#endif + /** @brief Enumeration of VTOL states */ #ifndef HAVE_ENUM_MAV_VTOL_STATE #define HAVE_ENUM_MAV_VTOL_STATE @@ -812,7 +1385,9 @@ typedef enum MAV_LANDED_STATE MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */ MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */ MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */ - MAV_LANDED_STATE_ENUM_END=3, /* | */ + MAV_LANDED_STATE_TAKEOFF=3, /* MAV currently taking off | */ + MAV_LANDED_STATE_LANDING=4, /* MAV currently landing | */ + MAV_LANDED_STATE_ENUM_END=5, /* | */ } MAV_LANDED_STATE; #endif @@ -868,11 +1443,14 @@ typedef enum ADSB_FLAGS ADSB_FLAGS_VALID_CALLSIGN=16, /* | */ ADSB_FLAGS_VALID_SQUAWK=32, /* | */ ADSB_FLAGS_SIMULATED=64, /* | */ - ADSB_FLAGS_ENUM_END=65, /* | */ + ADSB_FLAGS_VERTICAL_VELOCITY_VALID=128, /* | */ + ADSB_FLAGS_BARO_VALID=256, /* | */ + ADSB_FLAGS_SOURCE_UAT=32768, /* | */ + ADSB_FLAGS_ENUM_END=32769, /* | */ } ADSB_FLAGS; #endif -/** @brief Bitmask of options for the MAV_CMD_DO_REPOSITION */ +/** @brief Bitmap of options for the MAV_CMD_DO_REPOSITION */ #ifndef HAVE_ENUM_MAV_DO_REPOSITION_FLAGS #define HAVE_ENUM_MAV_DO_REPOSITION_FLAGS typedef enum MAV_DO_REPOSITION_FLAGS @@ -882,7 +1460,7 @@ typedef enum MAV_DO_REPOSITION_FLAGS } MAV_DO_REPOSITION_FLAGS; #endif -/** @brief Flags in EKF_STATUS message */ +/** @brief Flags in ESTIMATOR_STATUS message */ #ifndef HAVE_ENUM_ESTIMATOR_STATUS_FLAGS #define HAVE_ENUM_ESTIMATOR_STATUS_FLAGS typedef enum ESTIMATOR_STATUS_FLAGS @@ -898,10 +1476,23 @@ typedef enum ESTIMATOR_STATUS_FLAGS ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */ ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */ ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */ - ESTIMATOR_STATUS_FLAGS_ENUM_END=1025, /* | */ + ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */ + ESTIMATOR_STATUS_FLAGS_ENUM_END=2049, /* | */ } ESTIMATOR_STATUS_FLAGS; #endif +/** @brief */ +#ifndef HAVE_ENUM_MOTOR_TEST_ORDER +#define HAVE_ENUM_MOTOR_TEST_ORDER +typedef enum MOTOR_TEST_ORDER +{ + MOTOR_TEST_ORDER_DEFAULT=0, /* default autopilot motor test method | */ + MOTOR_TEST_ORDER_SEQUENCE=1, /* motor numbers are specified as their index in a predefined vehicle-specific sequence | */ + MOTOR_TEST_ORDER_BOARD=2, /* motor numbers are specified as the output as labeled on the board | */ + MOTOR_TEST_ORDER_ENUM_END=3, /* | */ +} MOTOR_TEST_ORDER; +#endif + /** @brief */ #ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE #define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE @@ -910,7 +1501,8 @@ typedef enum MOTOR_TEST_THROTTLE_TYPE MOTOR_TEST_THROTTLE_PERCENT=0, /* throttle as a percentage from 0 ~ 100 | */ MOTOR_TEST_THROTTLE_PWM=1, /* throttle as an absolute PWM value (normally in range of 1000~2000) | */ MOTOR_TEST_THROTTLE_PILOT=2, /* throttle pass-through from pilot's transmitter | */ - MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */ + MOTOR_TEST_COMPASS_CAL=3, /* per-motor compass calibration test | */ + MOTOR_TEST_THROTTLE_TYPE_ENUM_END=4, /* | */ } MOTOR_TEST_THROTTLE_TYPE; #endif @@ -954,7 +1546,7 @@ typedef enum MAV_COLLISION_THREAT_LEVEL { MAV_COLLISION_THREAT_LEVEL_NONE=0, /* Not a threat | */ MAV_COLLISION_THREAT_LEVEL_LOW=1, /* Craft is mildly concerned about this threat | */ - MAV_COLLISION_THREAT_LEVEL_HIGH=2, /* Craft is panicing, and may take actions to avoid threat | */ + MAV_COLLISION_THREAT_LEVEL_HIGH=2, /* Craft is panicking, and may take actions to avoid threat | */ MAV_COLLISION_THREAT_LEVEL_ENUM_END=3, /* | */ } MAV_COLLISION_THREAT_LEVEL; #endif @@ -983,10 +1575,811 @@ typedef enum GPS_FIX_TYPE GPS_FIX_TYPE_RTK_FLOAT=5, /* RTK float, 3D position | */ GPS_FIX_TYPE_RTK_FIXED=6, /* RTK Fixed, 3D position | */ GPS_FIX_TYPE_STATIC=7, /* Static fixed, typically used for base stations | */ - GPS_FIX_TYPE_ENUM_END=8, /* | */ + GPS_FIX_TYPE_PPP=8, /* PPP, 3D position. | */ + GPS_FIX_TYPE_ENUM_END=9, /* | */ } GPS_FIX_TYPE; #endif +/** @brief RTK GPS baseline coordinate system, used for RTK corrections */ +#ifndef HAVE_ENUM_RTK_BASELINE_COORDINATE_SYSTEM +#define HAVE_ENUM_RTK_BASELINE_COORDINATE_SYSTEM +typedef enum RTK_BASELINE_COORDINATE_SYSTEM +{ + RTK_BASELINE_COORDINATE_SYSTEM_ECEF=0, /* Earth-centered, Earth-fixed | */ + RTK_BASELINE_COORDINATE_SYSTEM_NED=1, /* RTK basestation centered, north, east, down | */ + RTK_BASELINE_COORDINATE_SYSTEM_ENUM_END=2, /* | */ +} RTK_BASELINE_COORDINATE_SYSTEM; +#endif + +/** @brief Type of landing target */ +#ifndef HAVE_ENUM_LANDING_TARGET_TYPE +#define HAVE_ENUM_LANDING_TARGET_TYPE +typedef enum LANDING_TARGET_TYPE +{ + LANDING_TARGET_TYPE_LIGHT_BEACON=0, /* Landing target signaled by light beacon (ex: IR-LOCK) | */ + LANDING_TARGET_TYPE_RADIO_BEACON=1, /* Landing target signaled by radio beacon (ex: ILS, NDB) | */ + LANDING_TARGET_TYPE_VISION_FIDUCIAL=2, /* Landing target represented by a fiducial marker (ex: ARTag) | */ + LANDING_TARGET_TYPE_VISION_OTHER=3, /* Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square) | */ + LANDING_TARGET_TYPE_ENUM_END=4, /* | */ +} LANDING_TARGET_TYPE; +#endif + +/** @brief Direction of VTOL transition */ +#ifndef HAVE_ENUM_VTOL_TRANSITION_HEADING +#define HAVE_ENUM_VTOL_TRANSITION_HEADING +typedef enum VTOL_TRANSITION_HEADING +{ + VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT=0, /* Respect the heading configuration of the vehicle. | */ + VTOL_TRANSITION_HEADING_NEXT_WAYPOINT=1, /* Use the heading pointing towards the next waypoint. | */ + VTOL_TRANSITION_HEADING_TAKEOFF=2, /* Use the heading on takeoff (while sitting on the ground). | */ + VTOL_TRANSITION_HEADING_SPECIFIED=3, /* Use the specified heading in parameter 4. | */ + VTOL_TRANSITION_HEADING_ANY=4, /* Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active). | */ + VTOL_TRANSITION_HEADING_ENUM_END=5, /* | */ +} VTOL_TRANSITION_HEADING; +#endif + +/** @brief Camera capability flags (Bitmap) */ +#ifndef HAVE_ENUM_CAMERA_CAP_FLAGS +#define HAVE_ENUM_CAMERA_CAP_FLAGS +typedef enum CAMERA_CAP_FLAGS +{ + CAMERA_CAP_FLAGS_CAPTURE_VIDEO=1, /* Camera is able to record video | */ + CAMERA_CAP_FLAGS_CAPTURE_IMAGE=2, /* Camera is able to capture images | */ + CAMERA_CAP_FLAGS_HAS_MODES=4, /* Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE) | */ + CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE=8, /* Camera can capture images while in video mode | */ + CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE=16, /* Camera can capture videos while in Photo/Image mode | */ + CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE=32, /* Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE) | */ + CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM=64, /* Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM) | */ + CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS=128, /* Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS) | */ + CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM=256, /* Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info) | */ + CAMERA_CAP_FLAGS_HAS_TRACKING_POINT=512, /* Camera supports tracking of a point on the camera view. | */ + CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE=1024, /* Camera supports tracking of a selection rectangle on the camera view. | */ + CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS=2048, /* Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS). | */ + CAMERA_CAP_FLAGS_ENUM_END=2049, /* | */ +} CAMERA_CAP_FLAGS; +#endif + +/** @brief Stream status flags (Bitmap) */ +#ifndef HAVE_ENUM_VIDEO_STREAM_STATUS_FLAGS +#define HAVE_ENUM_VIDEO_STREAM_STATUS_FLAGS +typedef enum VIDEO_STREAM_STATUS_FLAGS +{ + VIDEO_STREAM_STATUS_FLAGS_RUNNING=1, /* Stream is active (running) | */ + VIDEO_STREAM_STATUS_FLAGS_THERMAL=2, /* Stream is thermal imaging | */ + VIDEO_STREAM_STATUS_FLAGS_ENUM_END=3, /* | */ +} VIDEO_STREAM_STATUS_FLAGS; +#endif + +/** @brief Video stream types */ +#ifndef HAVE_ENUM_VIDEO_STREAM_TYPE +#define HAVE_ENUM_VIDEO_STREAM_TYPE +typedef enum VIDEO_STREAM_TYPE +{ + VIDEO_STREAM_TYPE_RTSP=0, /* Stream is RTSP | */ + VIDEO_STREAM_TYPE_RTPUDP=1, /* Stream is RTP UDP (URI gives the port number) | */ + VIDEO_STREAM_TYPE_TCP_MPEG=2, /* Stream is MPEG on TCP | */ + VIDEO_STREAM_TYPE_MPEG_TS_H264=3, /* Stream is h.264 on MPEG TS (URI gives the port number) | */ + VIDEO_STREAM_TYPE_ENUM_END=4, /* | */ +} VIDEO_STREAM_TYPE; +#endif + +/** @brief Camera tracking status flags */ +#ifndef HAVE_ENUM_CAMERA_TRACKING_STATUS_FLAGS +#define HAVE_ENUM_CAMERA_TRACKING_STATUS_FLAGS +typedef enum CAMERA_TRACKING_STATUS_FLAGS +{ + CAMERA_TRACKING_STATUS_FLAGS_IDLE=0, /* Camera is not tracking | */ + CAMERA_TRACKING_STATUS_FLAGS_ACTIVE=1, /* Camera is tracking | */ + CAMERA_TRACKING_STATUS_FLAGS_ERROR=2, /* Camera tracking in error state | */ + CAMERA_TRACKING_STATUS_FLAGS_ENUM_END=3, /* | */ +} CAMERA_TRACKING_STATUS_FLAGS; +#endif + +/** @brief Camera tracking modes */ +#ifndef HAVE_ENUM_CAMERA_TRACKING_MODE +#define HAVE_ENUM_CAMERA_TRACKING_MODE +typedef enum CAMERA_TRACKING_MODE +{ + CAMERA_TRACKING_NONE=0, /* Not tracking | */ + CAMERA_TRACKING_POINT=1, /* Target is a point | */ + CAMERA_TRACKING_RECTANGLE=2, /* Target is a rectangle | */ + CAMERA_TRACKING_MODE_ENUM_END=3, /* | */ +} CAMERA_TRACKING_MODE; +#endif + +/** @brief Camera tracking target data (shows where tracked target is within image) */ +#ifndef HAVE_ENUM_CAMERA_TRACKING_TARGET_DATA +#define HAVE_ENUM_CAMERA_TRACKING_TARGET_DATA +typedef enum CAMERA_TRACKING_TARGET_DATA +{ + CAMERA_TRACKING_TARGET_NONE=0, /* No target data | */ + CAMERA_TRACKING_TARGET_EMBEDDED=1, /* Target data embedded in image data (proprietary) | */ + CAMERA_TRACKING_TARGET_RENDERED=2, /* Target data rendered in image | */ + CAMERA_TRACKING_TARGET_IN_STATUS=4, /* Target data within status message (Point or Rectangle) | */ + CAMERA_TRACKING_TARGET_DATA_ENUM_END=5, /* | */ +} CAMERA_TRACKING_TARGET_DATA; +#endif + +/** @brief Zoom types for MAV_CMD_SET_CAMERA_ZOOM */ +#ifndef HAVE_ENUM_CAMERA_ZOOM_TYPE +#define HAVE_ENUM_CAMERA_ZOOM_TYPE +typedef enum CAMERA_ZOOM_TYPE +{ + ZOOM_TYPE_STEP=0, /* Zoom one step increment (-1 for wide, 1 for tele) | */ + ZOOM_TYPE_CONTINUOUS=1, /* Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming) | */ + ZOOM_TYPE_RANGE=2, /* Zoom value as proportion of full camera range (a value between 0.0 and 100.0) | */ + ZOOM_TYPE_FOCAL_LENGTH=3, /* Zoom value/variable focal length in milimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera) | */ + CAMERA_ZOOM_TYPE_ENUM_END=4, /* | */ +} CAMERA_ZOOM_TYPE; +#endif + +/** @brief Focus types for MAV_CMD_SET_CAMERA_FOCUS */ +#ifndef HAVE_ENUM_SET_FOCUS_TYPE +#define HAVE_ENUM_SET_FOCUS_TYPE +typedef enum SET_FOCUS_TYPE +{ + FOCUS_TYPE_STEP=0, /* Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity). | */ + FOCUS_TYPE_CONTINUOUS=1, /* Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing) | */ + FOCUS_TYPE_RANGE=2, /* Focus value as proportion of full camera focus range (a value between 0.0 and 100.0) | */ + FOCUS_TYPE_METERS=3, /* Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera). | */ + SET_FOCUS_TYPE_ENUM_END=4, /* | */ +} SET_FOCUS_TYPE; +#endif + +/** @brief Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction). */ +#ifndef HAVE_ENUM_PARAM_ACK +#define HAVE_ENUM_PARAM_ACK +typedef enum PARAM_ACK +{ + PARAM_ACK_ACCEPTED=0, /* Parameter value ACCEPTED and SET | */ + PARAM_ACK_VALUE_UNSUPPORTED=1, /* Parameter value UNKNOWN/UNSUPPORTED | */ + PARAM_ACK_FAILED=2, /* Parameter failed to set | */ + PARAM_ACK_IN_PROGRESS=3, /* Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating taht the the parameter was recieved and does not need to be resent. | */ + PARAM_ACK_ENUM_END=4, /* | */ +} PARAM_ACK; +#endif + +/** @brief Camera Modes. */ +#ifndef HAVE_ENUM_CAMERA_MODE +#define HAVE_ENUM_CAMERA_MODE +typedef enum CAMERA_MODE +{ + CAMERA_MODE_IMAGE=0, /* Camera is in image/photo capture mode. | */ + CAMERA_MODE_VIDEO=1, /* Camera is in video capture mode. | */ + CAMERA_MODE_IMAGE_SURVEY=2, /* Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys. | */ + CAMERA_MODE_ENUM_END=3, /* | */ +} CAMERA_MODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ARM_AUTH_DENIED_REASON +#define HAVE_ENUM_MAV_ARM_AUTH_DENIED_REASON +typedef enum MAV_ARM_AUTH_DENIED_REASON +{ + MAV_ARM_AUTH_DENIED_REASON_GENERIC=0, /* Not a specific reason | */ + MAV_ARM_AUTH_DENIED_REASON_NONE=1, /* Authorizer will send the error as string to GCS | */ + MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT=2, /* At least one waypoint have a invalid value | */ + MAV_ARM_AUTH_DENIED_REASON_TIMEOUT=3, /* Timeout in the authorizer process(in case it depends on network) | */ + MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE=4, /* Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied. | */ + MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER=5, /* Weather is not good to fly | */ + MAV_ARM_AUTH_DENIED_REASON_ENUM_END=6, /* | */ +} MAV_ARM_AUTH_DENIED_REASON; +#endif + +/** @brief RC type */ +#ifndef HAVE_ENUM_RC_TYPE +#define HAVE_ENUM_RC_TYPE +typedef enum RC_TYPE +{ + RC_TYPE_SPEKTRUM_DSM2=0, /* Spektrum DSM2 | */ + RC_TYPE_SPEKTRUM_DSMX=1, /* Spektrum DSMX | */ + RC_TYPE_ENUM_END=2, /* | */ +} RC_TYPE; +#endif + +/** @brief Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration. */ +#ifndef HAVE_ENUM_POSITION_TARGET_TYPEMASK +#define HAVE_ENUM_POSITION_TARGET_TYPEMASK +typedef enum POSITION_TARGET_TYPEMASK +{ + POSITION_TARGET_TYPEMASK_X_IGNORE=1, /* Ignore position x | */ + POSITION_TARGET_TYPEMASK_Y_IGNORE=2, /* Ignore position y | */ + POSITION_TARGET_TYPEMASK_Z_IGNORE=4, /* Ignore position z | */ + POSITION_TARGET_TYPEMASK_VX_IGNORE=8, /* Ignore velocity x | */ + POSITION_TARGET_TYPEMASK_VY_IGNORE=16, /* Ignore velocity y | */ + POSITION_TARGET_TYPEMASK_VZ_IGNORE=32, /* Ignore velocity z | */ + POSITION_TARGET_TYPEMASK_AX_IGNORE=64, /* Ignore acceleration x | */ + POSITION_TARGET_TYPEMASK_AY_IGNORE=128, /* Ignore acceleration y | */ + POSITION_TARGET_TYPEMASK_AZ_IGNORE=256, /* Ignore acceleration z | */ + POSITION_TARGET_TYPEMASK_FORCE_SET=512, /* Use force instead of acceleration | */ + POSITION_TARGET_TYPEMASK_YAW_IGNORE=1024, /* Ignore yaw | */ + POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE=2048, /* Ignore yaw rate | */ + POSITION_TARGET_TYPEMASK_ENUM_END=2049, /* | */ +} POSITION_TARGET_TYPEMASK; +#endif + +/** @brief Airborne status of UAS. */ +#ifndef HAVE_ENUM_UTM_FLIGHT_STATE +#define HAVE_ENUM_UTM_FLIGHT_STATE +typedef enum UTM_FLIGHT_STATE +{ + UTM_FLIGHT_STATE_UNKNOWN=1, /* The flight state can't be determined. | */ + UTM_FLIGHT_STATE_GROUND=2, /* UAS on ground. | */ + UTM_FLIGHT_STATE_AIRBORNE=3, /* UAS airborne. | */ + UTM_FLIGHT_STATE_EMERGENCY=16, /* UAS is in an emergency flight state. | */ + UTM_FLIGHT_STATE_NOCTRL=32, /* UAS has no active controls. | */ + UTM_FLIGHT_STATE_ENUM_END=33, /* | */ +} UTM_FLIGHT_STATE; +#endif + +/** @brief Flags for the global position report. */ +#ifndef HAVE_ENUM_UTM_DATA_AVAIL_FLAGS +#define HAVE_ENUM_UTM_DATA_AVAIL_FLAGS +typedef enum UTM_DATA_AVAIL_FLAGS +{ + UTM_DATA_AVAIL_FLAGS_TIME_VALID=1, /* The field time contains valid data. | */ + UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE=2, /* The field uas_id contains valid data. | */ + UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE=4, /* The fields lat, lon and h_acc contain valid data. | */ + UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE=8, /* The fields alt and v_acc contain valid data. | */ + UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE=16, /* The field relative_alt contains valid data. | */ + UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE=32, /* The fields vx and vy contain valid data. | */ + UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE=64, /* The field vz contains valid data. | */ + UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE=128, /* The fields next_lat, next_lon and next_alt contain valid data. | */ + UTM_DATA_AVAIL_FLAGS_ENUM_END=129, /* | */ +} UTM_DATA_AVAIL_FLAGS; +#endif + +/** @brief Cellular network radio type */ +#ifndef HAVE_ENUM_CELLULAR_NETWORK_RADIO_TYPE +#define HAVE_ENUM_CELLULAR_NETWORK_RADIO_TYPE +typedef enum CELLULAR_NETWORK_RADIO_TYPE +{ + CELLULAR_NETWORK_RADIO_TYPE_NONE=0, /* | */ + CELLULAR_NETWORK_RADIO_TYPE_GSM=1, /* | */ + CELLULAR_NETWORK_RADIO_TYPE_CDMA=2, /* | */ + CELLULAR_NETWORK_RADIO_TYPE_WCDMA=3, /* | */ + CELLULAR_NETWORK_RADIO_TYPE_LTE=4, /* | */ + CELLULAR_NETWORK_RADIO_TYPE_ENUM_END=5, /* | */ +} CELLULAR_NETWORK_RADIO_TYPE; +#endif + +/** @brief These flags encode the cellular network status */ +#ifndef HAVE_ENUM_CELLULAR_STATUS_FLAG +#define HAVE_ENUM_CELLULAR_STATUS_FLAG +typedef enum CELLULAR_STATUS_FLAG +{ + CELLULAR_STATUS_FLAG_UNKNOWN=0, /* State unknown or not reportable. | */ + CELLULAR_STATUS_FLAG_FAILED=1, /* Modem is unusable | */ + CELLULAR_STATUS_FLAG_INITIALIZING=2, /* Modem is being initialized | */ + CELLULAR_STATUS_FLAG_LOCKED=3, /* Modem is locked | */ + CELLULAR_STATUS_FLAG_DISABLED=4, /* Modem is not enabled and is powered down | */ + CELLULAR_STATUS_FLAG_DISABLING=5, /* Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state | */ + CELLULAR_STATUS_FLAG_ENABLING=6, /* Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state | */ + CELLULAR_STATUS_FLAG_ENABLED=7, /* Modem is enabled and powered on but not registered with a network provider and not available for data connections | */ + CELLULAR_STATUS_FLAG_SEARCHING=8, /* Modem is searching for a network provider to register | */ + CELLULAR_STATUS_FLAG_REGISTERED=9, /* Modem is registered with a network provider, and data connections and messaging may be available for use | */ + CELLULAR_STATUS_FLAG_DISCONNECTING=10, /* Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated | */ + CELLULAR_STATUS_FLAG_CONNECTING=11, /* Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered | */ + CELLULAR_STATUS_FLAG_CONNECTED=12, /* One or more packet data bearers is active and connected | */ + CELLULAR_STATUS_FLAG_ENUM_END=13, /* | */ +} CELLULAR_STATUS_FLAG; +#endif + +/** @brief These flags are used to diagnose the failure state of CELLULAR_STATUS */ +#ifndef HAVE_ENUM_CELLULAR_NETWORK_FAILED_REASON +#define HAVE_ENUM_CELLULAR_NETWORK_FAILED_REASON +typedef enum CELLULAR_NETWORK_FAILED_REASON +{ + CELLULAR_NETWORK_FAILED_REASON_NONE=0, /* No error | */ + CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1, /* Error state is unknown | */ + CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2, /* SIM is required for the modem but missing | */ + CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3, /* SIM is available, but not usuable for connection | */ + CELLULAR_NETWORK_FAILED_REASON_ENUM_END=4, /* | */ +} CELLULAR_NETWORK_FAILED_REASON; +#endif + +/** @brief Precision land modes (used in MAV_CMD_NAV_LAND). */ +#ifndef HAVE_ENUM_PRECISION_LAND_MODE +#define HAVE_ENUM_PRECISION_LAND_MODE +typedef enum PRECISION_LAND_MODE +{ + PRECISION_LAND_MODE_DISABLED=0, /* Normal (non-precision) landing. | */ + PRECISION_LAND_MODE_OPPORTUNISTIC=1, /* Use precision landing if beacon detected when land command accepted, otherwise land normally. | */ + PRECISION_LAND_MODE_REQUIRED=2, /* Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found). | */ + PRECISION_LAND_MODE_ENUM_END=3, /* | */ +} PRECISION_LAND_MODE; +#endif + +/** @brief Parachute actions. Trigger release and enable/disable auto-release. */ +#ifndef HAVE_ENUM_PARACHUTE_ACTION +#define HAVE_ENUM_PARACHUTE_ACTION +typedef enum PARACHUTE_ACTION +{ + PARACHUTE_DISABLE=0, /* Disable auto-release of parachute (i.e. release triggered by crash detectors). | */ + PARACHUTE_ENABLE=1, /* Enable auto-release of parachute. | */ + PARACHUTE_RELEASE=2, /* Release parachute and kill motors. | */ + PARACHUTE_ACTION_ENUM_END=3, /* | */ +} PARACHUTE_ACTION; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_TUNNEL_PAYLOAD_TYPE +#define HAVE_ENUM_MAV_TUNNEL_PAYLOAD_TYPE +typedef enum MAV_TUNNEL_PAYLOAD_TYPE +{ + MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN=0, /* Encoding of payload unknown. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0=200, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1=201, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2=202, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3=203, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4=204, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5=205, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6=206, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7=207, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8=208, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9=209, /* Registered for STorM32 gimbal controller. | */ + MAV_TUNNEL_PAYLOAD_TYPE_ENUM_END=210, /* | */ +} MAV_TUNNEL_PAYLOAD_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_ID_TYPE +#define HAVE_ENUM_MAV_ODID_ID_TYPE +typedef enum MAV_ODID_ID_TYPE +{ + MAV_ODID_ID_TYPE_NONE=0, /* No type defined. | */ + MAV_ODID_ID_TYPE_SERIAL_NUMBER=1, /* Manufacturer Serial Number (ANSI/CTA-2063 format). | */ + MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID=2, /* CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]. | */ + MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID=3, /* UTM (Unmanned Traffic Management) assigned UUID (RFC4122). | */ + MAV_ODID_ID_TYPE_ENUM_END=4, /* | */ +} MAV_ODID_ID_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_UA_TYPE +#define HAVE_ENUM_MAV_ODID_UA_TYPE +typedef enum MAV_ODID_UA_TYPE +{ + MAV_ODID_UA_TYPE_NONE=0, /* No UA (Unmanned Aircraft) type defined. | */ + MAV_ODID_UA_TYPE_AEROPLANE=1, /* Aeroplane/Airplane. Fixed wing. | */ + MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR=2, /* Helicopter or multirotor. | */ + MAV_ODID_UA_TYPE_GYROPLANE=3, /* Gyroplane. | */ + MAV_ODID_UA_TYPE_HYBRID_LIFT=4, /* VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically. | */ + MAV_ODID_UA_TYPE_ORNITHOPTER=5, /* Ornithopter. | */ + MAV_ODID_UA_TYPE_GLIDER=6, /* Glider. | */ + MAV_ODID_UA_TYPE_KITE=7, /* Kite. | */ + MAV_ODID_UA_TYPE_FREE_BALLOON=8, /* Free Balloon. | */ + MAV_ODID_UA_TYPE_CAPTIVE_BALLOON=9, /* Captive Balloon. | */ + MAV_ODID_UA_TYPE_AIRSHIP=10, /* Airship. E.g. a blimp. | */ + MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE=11, /* Free Fall/Parachute (unpowered). | */ + MAV_ODID_UA_TYPE_ROCKET=12, /* Rocket. | */ + MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT=13, /* Tethered powered aircraft. | */ + MAV_ODID_UA_TYPE_GROUND_OBSTACLE=14, /* Ground Obstacle. | */ + MAV_ODID_UA_TYPE_OTHER=15, /* Other type of aircraft not listed earlier. | */ + MAV_ODID_UA_TYPE_ENUM_END=16, /* | */ +} MAV_ODID_UA_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_STATUS +#define HAVE_ENUM_MAV_ODID_STATUS +typedef enum MAV_ODID_STATUS +{ + MAV_ODID_STATUS_UNDECLARED=0, /* The status of the (UA) Unmanned Aircraft is undefined. | */ + MAV_ODID_STATUS_GROUND=1, /* The UA is on the ground. | */ + MAV_ODID_STATUS_AIRBORNE=2, /* The UA is in the air. | */ + MAV_ODID_STATUS_EMERGENCY=3, /* The UA is having an emergency. | */ + MAV_ODID_STATUS_ENUM_END=4, /* | */ +} MAV_ODID_STATUS; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_HEIGHT_REF +#define HAVE_ENUM_MAV_ODID_HEIGHT_REF +typedef enum MAV_ODID_HEIGHT_REF +{ + MAV_ODID_HEIGHT_REF_OVER_TAKEOFF=0, /* The height field is relative to the take-off location. | */ + MAV_ODID_HEIGHT_REF_OVER_GROUND=1, /* The height field is relative to ground. | */ + MAV_ODID_HEIGHT_REF_ENUM_END=2, /* | */ +} MAV_ODID_HEIGHT_REF; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_HOR_ACC +#define HAVE_ENUM_MAV_ODID_HOR_ACC +typedef enum MAV_ODID_HOR_ACC +{ + MAV_ODID_HOR_ACC_UNKNOWN=0, /* The horizontal accuracy is unknown. | */ + MAV_ODID_HOR_ACC_10NM=1, /* The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km. | */ + MAV_ODID_HOR_ACC_4NM=2, /* The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km. | */ + MAV_ODID_HOR_ACC_2NM=3, /* The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km. | */ + MAV_ODID_HOR_ACC_1NM=4, /* The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km. | */ + MAV_ODID_HOR_ACC_0_5NM=5, /* The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m. | */ + MAV_ODID_HOR_ACC_0_3NM=6, /* The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m. | */ + MAV_ODID_HOR_ACC_0_1NM=7, /* The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m. | */ + MAV_ODID_HOR_ACC_0_05NM=8, /* The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m. | */ + MAV_ODID_HOR_ACC_30_METER=9, /* The horizontal accuracy is smaller than 30 meter. | */ + MAV_ODID_HOR_ACC_10_METER=10, /* The horizontal accuracy is smaller than 10 meter. | */ + MAV_ODID_HOR_ACC_3_METER=11, /* The horizontal accuracy is smaller than 3 meter. | */ + MAV_ODID_HOR_ACC_1_METER=12, /* The horizontal accuracy is smaller than 1 meter. | */ + MAV_ODID_HOR_ACC_ENUM_END=13, /* | */ +} MAV_ODID_HOR_ACC; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_VER_ACC +#define HAVE_ENUM_MAV_ODID_VER_ACC +typedef enum MAV_ODID_VER_ACC +{ + MAV_ODID_VER_ACC_UNKNOWN=0, /* The vertical accuracy is unknown. | */ + MAV_ODID_VER_ACC_150_METER=1, /* The vertical accuracy is smaller than 150 meter. | */ + MAV_ODID_VER_ACC_45_METER=2, /* The vertical accuracy is smaller than 45 meter. | */ + MAV_ODID_VER_ACC_25_METER=3, /* The vertical accuracy is smaller than 25 meter. | */ + MAV_ODID_VER_ACC_10_METER=4, /* The vertical accuracy is smaller than 10 meter. | */ + MAV_ODID_VER_ACC_3_METER=5, /* The vertical accuracy is smaller than 3 meter. | */ + MAV_ODID_VER_ACC_1_METER=6, /* The vertical accuracy is smaller than 1 meter. | */ + MAV_ODID_VER_ACC_ENUM_END=7, /* | */ +} MAV_ODID_VER_ACC; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_SPEED_ACC +#define HAVE_ENUM_MAV_ODID_SPEED_ACC +typedef enum MAV_ODID_SPEED_ACC +{ + MAV_ODID_SPEED_ACC_UNKNOWN=0, /* The speed accuracy is unknown. | */ + MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND=1, /* The speed accuracy is smaller than 10 meters per second. | */ + MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND=2, /* The speed accuracy is smaller than 3 meters per second. | */ + MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND=3, /* The speed accuracy is smaller than 1 meters per second. | */ + MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND=4, /* The speed accuracy is smaller than 0.3 meters per second. | */ + MAV_ODID_SPEED_ACC_ENUM_END=5, /* | */ +} MAV_ODID_SPEED_ACC; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_TIME_ACC +#define HAVE_ENUM_MAV_ODID_TIME_ACC +typedef enum MAV_ODID_TIME_ACC +{ + MAV_ODID_TIME_ACC_UNKNOWN=0, /* The timestamp accuracy is unknown. | */ + MAV_ODID_TIME_ACC_0_1_SECOND=1, /* The timestamp accuracy is smaller than or equal to 0.1 second. | */ + MAV_ODID_TIME_ACC_0_2_SECOND=2, /* The timestamp accuracy is smaller than or equal to 0.2 second. | */ + MAV_ODID_TIME_ACC_0_3_SECOND=3, /* The timestamp accuracy is smaller than or equal to 0.3 second. | */ + MAV_ODID_TIME_ACC_0_4_SECOND=4, /* The timestamp accuracy is smaller than or equal to 0.4 second. | */ + MAV_ODID_TIME_ACC_0_5_SECOND=5, /* The timestamp accuracy is smaller than or equal to 0.5 second. | */ + MAV_ODID_TIME_ACC_0_6_SECOND=6, /* The timestamp accuracy is smaller than or equal to 0.6 second. | */ + MAV_ODID_TIME_ACC_0_7_SECOND=7, /* The timestamp accuracy is smaller than or equal to 0.7 second. | */ + MAV_ODID_TIME_ACC_0_8_SECOND=8, /* The timestamp accuracy is smaller than or equal to 0.8 second. | */ + MAV_ODID_TIME_ACC_0_9_SECOND=9, /* The timestamp accuracy is smaller than or equal to 0.9 second. | */ + MAV_ODID_TIME_ACC_1_0_SECOND=10, /* The timestamp accuracy is smaller than or equal to 1.0 second. | */ + MAV_ODID_TIME_ACC_1_1_SECOND=11, /* The timestamp accuracy is smaller than or equal to 1.1 second. | */ + MAV_ODID_TIME_ACC_1_2_SECOND=12, /* The timestamp accuracy is smaller than or equal to 1.2 second. | */ + MAV_ODID_TIME_ACC_1_3_SECOND=13, /* The timestamp accuracy is smaller than or equal to 1.3 second. | */ + MAV_ODID_TIME_ACC_1_4_SECOND=14, /* The timestamp accuracy is smaller than or equal to 1.4 second. | */ + MAV_ODID_TIME_ACC_1_5_SECOND=15, /* The timestamp accuracy is smaller than or equal to 1.5 second. | */ + MAV_ODID_TIME_ACC_ENUM_END=16, /* | */ +} MAV_ODID_TIME_ACC; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_AUTH_TYPE +#define HAVE_ENUM_MAV_ODID_AUTH_TYPE +typedef enum MAV_ODID_AUTH_TYPE +{ + MAV_ODID_AUTH_TYPE_NONE=0, /* No authentication type is specified. | */ + MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE=1, /* Signature for the UAS (Unmanned Aircraft System) ID. | */ + MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE=2, /* Signature for the Operator ID. | */ + MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE=3, /* Signature for the entire message set. | */ + MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID=4, /* Authentication is provided by Network Remote ID. | */ + MAV_ODID_AUTH_TYPE_ENUM_END=5, /* | */ +} MAV_ODID_AUTH_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_DESC_TYPE +#define HAVE_ENUM_MAV_ODID_DESC_TYPE +typedef enum MAV_ODID_DESC_TYPE +{ + MAV_ODID_DESC_TYPE_TEXT=0, /* Free-form text description of the purpose of the flight. | */ + MAV_ODID_DESC_TYPE_ENUM_END=1, /* | */ +} MAV_ODID_DESC_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_OPERATOR_LOCATION_TYPE +#define HAVE_ENUM_MAV_ODID_OPERATOR_LOCATION_TYPE +typedef enum MAV_ODID_OPERATOR_LOCATION_TYPE +{ + MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF=0, /* The location of the operator is the same as the take-off location. | */ + MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS=1, /* The location of the operator is based on live GNSS data. | */ + MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED=2, /* The location of the operator is a fixed location. | */ + MAV_ODID_OPERATOR_LOCATION_TYPE_ENUM_END=3, /* | */ +} MAV_ODID_OPERATOR_LOCATION_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_CLASSIFICATION_TYPE +#define HAVE_ENUM_MAV_ODID_CLASSIFICATION_TYPE +typedef enum MAV_ODID_CLASSIFICATION_TYPE +{ + MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED=0, /* The classification type for the UA is undeclared. | */ + MAV_ODID_CLASSIFICATION_TYPE_EU=1, /* The classification type for the UA follows EU (European Union) specifications. | */ + MAV_ODID_CLASSIFICATION_TYPE_ENUM_END=2, /* | */ +} MAV_ODID_CLASSIFICATION_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_CATEGORY_EU +#define HAVE_ENUM_MAV_ODID_CATEGORY_EU +typedef enum MAV_ODID_CATEGORY_EU +{ + MAV_ODID_CATEGORY_EU_UNDECLARED=0, /* The category for the UA, according to the EU specification, is undeclared. | */ + MAV_ODID_CATEGORY_EU_OPEN=1, /* The category for the UA, according to the EU specification, is the Open category. | */ + MAV_ODID_CATEGORY_EU_SPECIFIC=2, /* The category for the UA, according to the EU specification, is the Specific category. | */ + MAV_ODID_CATEGORY_EU_CERTIFIED=3, /* The category for the UA, according to the EU specification, is the Certified category. | */ + MAV_ODID_CATEGORY_EU_ENUM_END=4, /* | */ +} MAV_ODID_CATEGORY_EU; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_CLASS_EU +#define HAVE_ENUM_MAV_ODID_CLASS_EU +typedef enum MAV_ODID_CLASS_EU +{ + MAV_ODID_CLASS_EU_UNDECLARED=0, /* The class for the UA, according to the EU specification, is undeclared. | */ + MAV_ODID_CLASS_EU_CLASS_0=1, /* The class for the UA, according to the EU specification, is Class 0. | */ + MAV_ODID_CLASS_EU_CLASS_1=2, /* The class for the UA, according to the EU specification, is Class 1. | */ + MAV_ODID_CLASS_EU_CLASS_2=3, /* The class for the UA, according to the EU specification, is Class 2. | */ + MAV_ODID_CLASS_EU_CLASS_3=4, /* The class for the UA, according to the EU specification, is Class 3. | */ + MAV_ODID_CLASS_EU_CLASS_4=5, /* The class for the UA, according to the EU specification, is Class 4. | */ + MAV_ODID_CLASS_EU_CLASS_5=6, /* The class for the UA, according to the EU specification, is Class 5. | */ + MAV_ODID_CLASS_EU_CLASS_6=7, /* The class for the UA, according to the EU specification, is Class 6. | */ + MAV_ODID_CLASS_EU_ENUM_END=8, /* | */ +} MAV_ODID_CLASS_EU; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_ODID_OPERATOR_ID_TYPE +#define HAVE_ENUM_MAV_ODID_OPERATOR_ID_TYPE +typedef enum MAV_ODID_OPERATOR_ID_TYPE +{ + MAV_ODID_OPERATOR_ID_TYPE_CAA=0, /* CAA (Civil Aviation Authority) registered operator ID. | */ + MAV_ODID_OPERATOR_ID_TYPE_ENUM_END=1, /* | */ +} MAV_ODID_OPERATOR_ID_TYPE; +#endif + +/** @brief Tune formats (used for vehicle buzzer/tone generation). */ +#ifndef HAVE_ENUM_TUNE_FORMAT +#define HAVE_ENUM_TUNE_FORMAT +typedef enum TUNE_FORMAT +{ + TUNE_FORMAT_QBASIC1_1=1, /* Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm. | */ + TUNE_FORMAT_MML_MODERN=2, /* Format is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML. | */ + TUNE_FORMAT_ENUM_END=3, /* | */ +} TUNE_FORMAT; +#endif + +/** @brief Component capability flags (Bitmap) */ +#ifndef HAVE_ENUM_COMPONENT_CAP_FLAGS +#define HAVE_ENUM_COMPONENT_CAP_FLAGS +typedef enum COMPONENT_CAP_FLAGS +{ + COMPONENT_CAP_FLAGS_PARAM=1, /* Component has parameters, and supports the parameter protocol (PARAM messages). | */ + COMPONENT_CAP_FLAGS_PARAM_EXT=2, /* Component has parameters, and supports the extended parameter protocol (PARAM_EXT messages). | */ + COMPONENT_CAP_FLAGS_ENUM_END=3, /* | */ +} COMPONENT_CAP_FLAGS; +#endif + +/** @brief Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html */ +#ifndef HAVE_ENUM_AIS_TYPE +#define HAVE_ENUM_AIS_TYPE +typedef enum AIS_TYPE +{ + AIS_TYPE_UNKNOWN=0, /* Not available (default). | */ + AIS_TYPE_RESERVED_1=1, /* | */ + AIS_TYPE_RESERVED_2=2, /* | */ + AIS_TYPE_RESERVED_3=3, /* | */ + AIS_TYPE_RESERVED_4=4, /* | */ + AIS_TYPE_RESERVED_5=5, /* | */ + AIS_TYPE_RESERVED_6=6, /* | */ + AIS_TYPE_RESERVED_7=7, /* | */ + AIS_TYPE_RESERVED_8=8, /* | */ + AIS_TYPE_RESERVED_9=9, /* | */ + AIS_TYPE_RESERVED_10=10, /* | */ + AIS_TYPE_RESERVED_11=11, /* | */ + AIS_TYPE_RESERVED_12=12, /* | */ + AIS_TYPE_RESERVED_13=13, /* | */ + AIS_TYPE_RESERVED_14=14, /* | */ + AIS_TYPE_RESERVED_15=15, /* | */ + AIS_TYPE_RESERVED_16=16, /* | */ + AIS_TYPE_RESERVED_17=17, /* | */ + AIS_TYPE_RESERVED_18=18, /* | */ + AIS_TYPE_RESERVED_19=19, /* | */ + AIS_TYPE_WIG=20, /* Wing In Ground effect. | */ + AIS_TYPE_WIG_HAZARDOUS_A=21, /* | */ + AIS_TYPE_WIG_HAZARDOUS_B=22, /* | */ + AIS_TYPE_WIG_HAZARDOUS_C=23, /* | */ + AIS_TYPE_WIG_HAZARDOUS_D=24, /* | */ + AIS_TYPE_WIG_RESERVED_1=25, /* | */ + AIS_TYPE_WIG_RESERVED_2=26, /* | */ + AIS_TYPE_WIG_RESERVED_3=27, /* | */ + AIS_TYPE_WIG_RESERVED_4=28, /* | */ + AIS_TYPE_WIG_RESERVED_5=29, /* | */ + AIS_TYPE_FISHING=30, /* | */ + AIS_TYPE_TOWING=31, /* | */ + AIS_TYPE_TOWING_LARGE=32, /* Towing: length exceeds 200m or breadth exceeds 25m. | */ + AIS_TYPE_DREDGING=33, /* Dredging or other underwater ops. | */ + AIS_TYPE_DIVING=34, /* | */ + AIS_TYPE_MILITARY=35, /* | */ + AIS_TYPE_SAILING=36, /* | */ + AIS_TYPE_PLEASURE=37, /* | */ + AIS_TYPE_RESERVED_20=38, /* | */ + AIS_TYPE_RESERVED_21=39, /* | */ + AIS_TYPE_HSC=40, /* High Speed Craft. | */ + AIS_TYPE_HSC_HAZARDOUS_A=41, /* | */ + AIS_TYPE_HSC_HAZARDOUS_B=42, /* | */ + AIS_TYPE_HSC_HAZARDOUS_C=43, /* | */ + AIS_TYPE_HSC_HAZARDOUS_D=44, /* | */ + AIS_TYPE_HSC_RESERVED_1=45, /* | */ + AIS_TYPE_HSC_RESERVED_2=46, /* | */ + AIS_TYPE_HSC_RESERVED_3=47, /* | */ + AIS_TYPE_HSC_RESERVED_4=48, /* | */ + AIS_TYPE_HSC_UNKNOWN=49, /* | */ + AIS_TYPE_PILOT=50, /* | */ + AIS_TYPE_SAR=51, /* Search And Rescue vessel. | */ + AIS_TYPE_TUG=52, /* | */ + AIS_TYPE_PORT_TENDER=53, /* | */ + AIS_TYPE_ANTI_POLLUTION=54, /* Anti-pollution equipment. | */ + AIS_TYPE_LAW_ENFORCEMENT=55, /* | */ + AIS_TYPE_SPARE_LOCAL_1=56, /* | */ + AIS_TYPE_SPARE_LOCAL_2=57, /* | */ + AIS_TYPE_MEDICAL_TRANSPORT=58, /* | */ + AIS_TYPE_NONECOMBATANT=59, /* Noncombatant ship according to RR Resolution No. 18. | */ + AIS_TYPE_PASSENGER=60, /* | */ + AIS_TYPE_PASSENGER_HAZARDOUS_A=61, /* | */ + AIS_TYPE_PASSENGER_HAZARDOUS_B=62, /* | */ + AIS_TYPE_AIS_TYPE_PASSENGER_HAZARDOUS_C=63, /* | */ + AIS_TYPE_PASSENGER_HAZARDOUS_D=64, /* | */ + AIS_TYPE_PASSENGER_RESERVED_1=65, /* | */ + AIS_TYPE_PASSENGER_RESERVED_2=66, /* | */ + AIS_TYPE_PASSENGER_RESERVED_3=67, /* | */ + AIS_TYPE_AIS_TYPE_PASSENGER_RESERVED_4=68, /* | */ + AIS_TYPE_PASSENGER_UNKNOWN=69, /* | */ + AIS_TYPE_CARGO=70, /* | */ + AIS_TYPE_CARGO_HAZARDOUS_A=71, /* | */ + AIS_TYPE_CARGO_HAZARDOUS_B=72, /* | */ + AIS_TYPE_CARGO_HAZARDOUS_C=73, /* | */ + AIS_TYPE_CARGO_HAZARDOUS_D=74, /* | */ + AIS_TYPE_CARGO_RESERVED_1=75, /* | */ + AIS_TYPE_CARGO_RESERVED_2=76, /* | */ + AIS_TYPE_CARGO_RESERVED_3=77, /* | */ + AIS_TYPE_CARGO_RESERVED_4=78, /* | */ + AIS_TYPE_CARGO_UNKNOWN=79, /* | */ + AIS_TYPE_TANKER=80, /* | */ + AIS_TYPE_TANKER_HAZARDOUS_A=81, /* | */ + AIS_TYPE_TANKER_HAZARDOUS_B=82, /* | */ + AIS_TYPE_TANKER_HAZARDOUS_C=83, /* | */ + AIS_TYPE_TANKER_HAZARDOUS_D=84, /* | */ + AIS_TYPE_TANKER_RESERVED_1=85, /* | */ + AIS_TYPE_TANKER_RESERVED_2=86, /* | */ + AIS_TYPE_TANKER_RESERVED_3=87, /* | */ + AIS_TYPE_TANKER_RESERVED_4=88, /* | */ + AIS_TYPE_TANKER_UNKNOWN=89, /* | */ + AIS_TYPE_OTHER=90, /* | */ + AIS_TYPE_OTHER_HAZARDOUS_A=91, /* | */ + AIS_TYPE_OTHER_HAZARDOUS_B=92, /* | */ + AIS_TYPE_OTHER_HAZARDOUS_C=93, /* | */ + AIS_TYPE_OTHER_HAZARDOUS_D=94, /* | */ + AIS_TYPE_OTHER_RESERVED_1=95, /* | */ + AIS_TYPE_OTHER_RESERVED_2=96, /* | */ + AIS_TYPE_OTHER_RESERVED_3=97, /* | */ + AIS_TYPE_OTHER_RESERVED_4=98, /* | */ + AIS_TYPE_OTHER_UNKNOWN=99, /* | */ + AIS_TYPE_ENUM_END=100, /* | */ +} AIS_TYPE; +#endif + +/** @brief Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html */ +#ifndef HAVE_ENUM_AIS_NAV_STATUS +#define HAVE_ENUM_AIS_NAV_STATUS +typedef enum AIS_NAV_STATUS +{ + UNDER_WAY=0, /* Under way using engine. | */ + AIS_NAV_ANCHORED=1, /* | */ + AIS_NAV_UN_COMMANDED=2, /* | */ + AIS_NAV_RESTRICTED_MANOEUVERABILITY=3, /* | */ + AIS_NAV_DRAUGHT_CONSTRAINED=4, /* | */ + AIS_NAV_MOORED=5, /* | */ + AIS_NAV_AGROUND=6, /* | */ + AIS_NAV_FISHING=7, /* | */ + AIS_NAV_SAILING=8, /* | */ + AIS_NAV_RESERVED_HSC=9, /* | */ + AIS_NAV_RESERVED_WIG=10, /* | */ + AIS_NAV_RESERVED_1=11, /* | */ + AIS_NAV_RESERVED_2=12, /* | */ + AIS_NAV_RESERVED_3=13, /* | */ + AIS_NAV_AIS_SART=14, /* Search And Rescue Transponder. | */ + AIS_NAV_UNKNOWN=15, /* Not available (default). | */ + AIS_NAV_STATUS_ENUM_END=16, /* | */ +} AIS_NAV_STATUS; +#endif + +/** @brief These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid. */ +#ifndef HAVE_ENUM_AIS_FLAGS +#define HAVE_ENUM_AIS_FLAGS +typedef enum AIS_FLAGS +{ + AIS_FLAGS_POSITION_ACCURACY=1, /* 1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m. | */ + AIS_FLAGS_VALID_COG=2, /* | */ + AIS_FLAGS_VALID_VELOCITY=4, /* | */ + AIS_FLAGS_HIGH_VELOCITY=8, /* 1 = Velocity over 52.5765m/s (102.2 knots) | */ + AIS_FLAGS_VALID_TURN_RATE=16, /* | */ + AIS_FLAGS_TURN_RATE_SIGN_ONLY=32, /* Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s | */ + AIS_FLAGS_VALID_DIMENSIONS=64, /* | */ + AIS_FLAGS_LARGE_BOW_DIMENSION=128, /* Distance to bow is larger than 511m | */ + AIS_FLAGS_LARGE_STERN_DIMENSION=256, /* Distance to stern is larger than 511m | */ + AIS_FLAGS_LARGE_PORT_DIMENSION=512, /* Distance to port side is larger than 63m | */ + AIS_FLAGS_LARGE_STARBOARD_DIMENSION=1024, /* Distance to starboard side is larger than 63m | */ + AIS_FLAGS_VALID_CALLSIGN=2048, /* | */ + AIS_FLAGS_VALID_NAME=4096, /* | */ + AIS_FLAGS_ENUM_END=4097, /* | */ +} AIS_FLAGS; +#endif + +/** @brief List of possible units where failures can be injected. */ +#ifndef HAVE_ENUM_FAILURE_UNIT +#define HAVE_ENUM_FAILURE_UNIT +typedef enum FAILURE_UNIT +{ + FAILURE_UNIT_SENSOR_GYRO=0, /* | */ + FAILURE_UNIT_SENSOR_ACCEL=1, /* | */ + FAILURE_UNIT_SENSOR_MAG=2, /* | */ + FAILURE_UNIT_SENSOR_BARO=3, /* | */ + FAILURE_UNIT_SENSOR_GPS=4, /* | */ + FAILURE_UNIT_SENSOR_OPTICAL_FLOW=5, /* | */ + FAILURE_UNIT_SENSOR_VIO=6, /* | */ + FAILURE_UNIT_SENSOR_DISTANCE_SENSOR=7, /* | */ + FAILURE_UNIT_SENSOR_AIRSPEED=8, /* | */ + FAILURE_UNIT_SYSTEM_BATTERY=100, /* | */ + FAILURE_UNIT_SYSTEM_MOTOR=101, /* | */ + FAILURE_UNIT_SYSTEM_SERVO=102, /* | */ + FAILURE_UNIT_SYSTEM_AVOIDANCE=103, /* | */ + FAILURE_UNIT_SYSTEM_RC_SIGNAL=104, /* | */ + FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL=105, /* | */ + FAILURE_UNIT_ENUM_END=106, /* | */ +} FAILURE_UNIT; +#endif + +/** @brief List of possible failure type to inject. */ +#ifndef HAVE_ENUM_FAILURE_TYPE +#define HAVE_ENUM_FAILURE_TYPE +typedef enum FAILURE_TYPE +{ + FAILURE_TYPE_OK=0, /* No failure injected, used to reset a previous failure. | */ + FAILURE_TYPE_OFF=1, /* Sets unit off, so completely non-responsive. | */ + FAILURE_TYPE_STUCK=2, /* Unit is stuck e.g. keeps reporting the same value. | */ + FAILURE_TYPE_GARBAGE=3, /* Unit is reporting complete garbage. | */ + FAILURE_TYPE_WRONG=4, /* Unit is consistently wrong. | */ + FAILURE_TYPE_SLOW=5, /* Unit is slow, so e.g. reporting at slower than expected rate. | */ + FAILURE_TYPE_DELAYED=6, /* Data of unit is delayed in time. | */ + FAILURE_TYPE_INTERMITTENT=7, /* Unit is sometimes working, sometimes not. | */ + FAILURE_TYPE_ENUM_END=8, /* | */ +} FAILURE_TYPE; +#endif + +/** @brief Winch status flags used in WINCH_STATUS */ +#ifndef HAVE_ENUM_MAV_WINCH_STATUS_FLAG +#define HAVE_ENUM_MAV_WINCH_STATUS_FLAG +typedef enum MAV_WINCH_STATUS_FLAG +{ + MAV_WINCH_STATUS_HEALTHY=1, /* Winch is healthy | */ + MAV_WINCH_STATUS_FULLY_RETRACTED=2, /* Winch thread is fully retracted | */ + MAV_WINCH_STATUS_MOVING=4, /* Winch motor is moving | */ + MAV_WINCH_STATUS_CLUTCH_ENGAGED=8, /* Winch clutch is engaged allowing motor to move freely | */ + MAV_WINCH_STATUS_FLAG_ENUM_END=9, /* | */ +} MAV_WINCH_STATUS_FLAG; +#endif + // MAVLINK VERSION #ifndef MAVLINK_VERSION @@ -1006,7 +2399,9 @@ typedef enum GPS_FIX_TYPE #include "./mavlink_msg_change_operator_control.h" #include "./mavlink_msg_change_operator_control_ack.h" #include "./mavlink_msg_auth_key.h" +#include "./mavlink_msg_link_node_status.h" #include "./mavlink_msg_set_mode.h" +#include "./mavlink_msg_param_ack_transaction.h" #include "./mavlink_msg_param_request_read.h" #include "./mavlink_msg_param_request_list.h" #include "./mavlink_msg_param_value.h" @@ -1039,6 +2434,7 @@ typedef enum GPS_FIX_TYPE #include "./mavlink_msg_gps_global_origin.h" #include "./mavlink_msg_param_map_rc.h" #include "./mavlink_msg_mission_request_int.h" +#include "./mavlink_msg_mission_changed.h" #include "./mavlink_msg_safety_set_allowed_area.h" #include "./mavlink_msg_safety_allowed_area.h" #include "./mavlink_msg_attitude_quaternion_cov.h" @@ -1055,6 +2451,7 @@ typedef enum GPS_FIX_TYPE #include "./mavlink_msg_command_int.h" #include "./mavlink_msg_command_long.h" #include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_command_cancel.h" #include "./mavlink_msg_manual_setpoint.h" #include "./mavlink_msg_set_attitude_target.h" #include "./mavlink_msg_attitude_target.h" @@ -1116,11 +2513,13 @@ typedef enum GPS_FIX_TYPE #include "./mavlink_msg_battery_status.h" #include "./mavlink_msg_autopilot_version.h" #include "./mavlink_msg_landing_target.h" +#include "./mavlink_msg_fence_status.h" #include "./mavlink_msg_estimator_status.h" #include "./mavlink_msg_wind_cov.h" #include "./mavlink_msg_gps_input.h" #include "./mavlink_msg_gps_rtcm_data.h" #include "./mavlink_msg_high_latency.h" +#include "./mavlink_msg_high_latency2.h" #include "./mavlink_msg_vibration.h" #include "./mavlink_msg_home_position.h" #include "./mavlink_msg_set_home_position.h" @@ -1140,10 +2539,11 @@ typedef enum GPS_FIX_TYPE #undef MAVLINK_THIS_XML_IDX -#define MAVLINK_THIS_XML_IDX 1 +#define MAVLINK_THIS_XML_IDX 0 #if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX -# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_ACK_TRANSACTION, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_MISSION_CHANGED, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_CANCEL, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_HIGH_LATENCY2, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +# define MAVLINK_MESSAGE_NAMES {{ "ACTUATOR_CONTROL_TARGET", 140 }, { "ADSB_VEHICLE", 246 }, { "ALTITUDE", 141 }, { "ATTITUDE", 30 }, { "ATTITUDE_QUATERNION", 31 }, { "ATTITUDE_QUATERNION_COV", 61 }, { "ATTITUDE_TARGET", 83 }, { "ATT_POS_MOCAP", 138 }, { "AUTH_KEY", 7 }, { "AUTOPILOT_VERSION", 148 }, { "BATTERY_STATUS", 147 }, { "CAMERA_TRIGGER", 112 }, { "CHANGE_OPERATOR_CONTROL", 5 }, { "CHANGE_OPERATOR_CONTROL_ACK", 6 }, { "COLLISION", 247 }, { "COMMAND_ACK", 77 }, { "COMMAND_CANCEL", 80 }, { "COMMAND_INT", 75 }, { "COMMAND_LONG", 76 }, { "CONTROL_SYSTEM_STATE", 146 }, { "DATA_STREAM", 67 }, { "DATA_TRANSMISSION_HANDSHAKE", 130 }, { "DEBUG", 254 }, { "DEBUG_VECT", 250 }, { "DISTANCE_SENSOR", 132 }, { "ENCAPSULATED_DATA", 131 }, { "ESTIMATOR_STATUS", 230 }, { "EXTENDED_SYS_STATE", 245 }, { "FENCE_STATUS", 162 }, { "FILE_TRANSFER_PROTOCOL", 110 }, { "FOLLOW_TARGET", 144 }, { "GLOBAL_POSITION_INT", 33 }, { "GLOBAL_POSITION_INT_COV", 63 }, { "GLOBAL_VISION_POSITION_ESTIMATE", 101 }, { "GPS2_RAW", 124 }, { "GPS2_RTK", 128 }, { "GPS_GLOBAL_ORIGIN", 49 }, { "GPS_INJECT_DATA", 123 }, { "GPS_INPUT", 232 }, { "GPS_RAW_INT", 24 }, { "GPS_RTCM_DATA", 233 }, { "GPS_RTK", 127 }, { "GPS_STATUS", 25 }, { "HEARTBEAT", 0 }, { "HIGHRES_IMU", 105 }, { "HIGH_LATENCY", 234 }, { "HIGH_LATENCY2", 235 }, { "HIL_ACTUATOR_CONTROLS", 93 }, { "HIL_CONTROLS", 91 }, { "HIL_GPS", 113 }, { "HIL_OPTICAL_FLOW", 114 }, { "HIL_RC_INPUTS_RAW", 92 }, { "HIL_SENSOR", 107 }, { "HIL_STATE", 90 }, { "HIL_STATE_QUATERNION", 115 }, { "HOME_POSITION", 242 }, { "LANDING_TARGET", 149 }, { "LINK_NODE_STATUS", 8 }, { "LOCAL_POSITION_NED", 32 }, { "LOCAL_POSITION_NED_COV", 64 }, { "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", 89 }, { "LOG_DATA", 120 }, { "LOG_ENTRY", 118 }, { "LOG_ERASE", 121 }, { "LOG_REQUEST_DATA", 119 }, { "LOG_REQUEST_END", 122 }, { "LOG_REQUEST_LIST", 117 }, { "MANUAL_CONTROL", 69 }, { "MANUAL_SETPOINT", 81 }, { "MEMORY_VECT", 249 }, { "MESSAGE_INTERVAL", 244 }, { "MISSION_ACK", 47 }, { "MISSION_CHANGED", 52 }, { "MISSION_CLEAR_ALL", 45 }, { "MISSION_COUNT", 44 }, { "MISSION_CURRENT", 42 }, { "MISSION_ITEM", 39 }, { "MISSION_ITEM_INT", 73 }, { "MISSION_ITEM_REACHED", 46 }, { "MISSION_REQUEST", 40 }, { "MISSION_REQUEST_INT", 51 }, { "MISSION_REQUEST_LIST", 43 }, { "MISSION_REQUEST_PARTIAL_LIST", 37 }, { "MISSION_SET_CURRENT", 41 }, { "MISSION_WRITE_PARTIAL_LIST", 38 }, { "NAMED_VALUE_FLOAT", 251 }, { "NAMED_VALUE_INT", 252 }, { "NAV_CONTROLLER_OUTPUT", 62 }, { "OPTICAL_FLOW", 100 }, { "OPTICAL_FLOW_RAD", 106 }, { "PARAM_ACK_TRANSACTION", 19 }, { "PARAM_MAP_RC", 50 }, { "PARAM_REQUEST_LIST", 21 }, { "PARAM_REQUEST_READ", 20 }, { "PARAM_SET", 23 }, { "PARAM_VALUE", 22 }, { "PING", 4 }, { "POSITION_TARGET_GLOBAL_INT", 87 }, { "POSITION_TARGET_LOCAL_NED", 85 }, { "POWER_STATUS", 125 }, { "RADIO_STATUS", 109 }, { "RAW_IMU", 27 }, { "RAW_PRESSURE", 28 }, { "RC_CHANNELS", 65 }, { "RC_CHANNELS_OVERRIDE", 70 }, { "RC_CHANNELS_RAW", 35 }, { "RC_CHANNELS_SCALED", 34 }, { "REQUEST_DATA_STREAM", 66 }, { "RESOURCE_REQUEST", 142 }, { "SAFETY_ALLOWED_AREA", 55 }, { "SAFETY_SET_ALLOWED_AREA", 54 }, { "SCALED_IMU", 26 }, { "SCALED_IMU2", 116 }, { "SCALED_IMU3", 129 }, { "SCALED_PRESSURE", 29 }, { "SCALED_PRESSURE2", 137 }, { "SCALED_PRESSURE3", 143 }, { "SERIAL_CONTROL", 126 }, { "SERVO_OUTPUT_RAW", 36 }, { "SET_ACTUATOR_CONTROL_TARGET", 139 }, { "SET_ATTITUDE_TARGET", 82 }, { "SET_GPS_GLOBAL_ORIGIN", 48 }, { "SET_HOME_POSITION", 243 }, { "SET_MODE", 11 }, { "SET_POSITION_TARGET_GLOBAL_INT", 86 }, { "SET_POSITION_TARGET_LOCAL_NED", 84 }, { "SIM_STATE", 108 }, { "STATUSTEXT", 253 }, { "SYSTEM_TIME", 2 }, { "SYS_STATUS", 1 }, { "TERRAIN_CHECK", 135 }, { "TERRAIN_DATA", 134 }, { "TERRAIN_REPORT", 136 }, { "TERRAIN_REQUEST", 133 }, { "TIMESYNC", 111 }, { "V2_EXTENSION", 248 }, { "VFR_HUD", 74 }, { "VIBRATION", 241 }, { "VICON_POSITION_ESTIMATE", 104 }, { "VISION_POSITION_ESTIMATE", 102 }, { "VISION_SPEED_ESTIMATE", 103 }, { "WIND_COV", 231 }} # if MAVLINK_COMMAND_24BIT # include "../mavlink_get_info.h" # endif diff --git a/lib/main/MAVLink/common/mavlink.h b/lib/main/MAVLink/common/mavlink.h index 6644aa5c2f..35163d3459 100755 --- a/lib/main/MAVLink/common/mavlink.h +++ b/lib/main/MAVLink/common/mavlink.h @@ -6,7 +6,7 @@ #ifndef MAVLINK_H #define MAVLINK_H -#define MAVLINK_PRIMARY_XML_IDX 1 +#define MAVLINK_PRIMARY_XML_IDX 0 #ifndef MAVLINK_STX #define MAVLINK_STX 254 diff --git a/lib/main/MAVLink/common/mavlink_msg_actuator_control_target.h b/lib/main/MAVLink/common/mavlink_msg_actuator_control_target.h index 2d1ebc05a2..31e307cb5a 100755 --- a/lib/main/MAVLink/common/mavlink_msg_actuator_control_target.h +++ b/lib/main/MAVLink/common/mavlink_msg_actuator_control_target.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 -MAVPACKED( + typedef struct __mavlink_actuator_control_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ -}) mavlink_actuator_control_target_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ + uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ +} mavlink_actuator_control_target_t; #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN 41 @@ -26,8 +26,8 @@ typedef struct __mavlink_actuator_control_target_t { "ACTUATOR_CONTROL_TARGET", \ 3, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ } \ } #else @@ -35,8 +35,8 @@ typedef struct __mavlink_actuator_control_target_t { "ACTUATOR_CONTROL_TARGET", \ 3, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_actuator_control_target_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -79,9 +79,9 @@ static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_i * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -137,9 +137,9 @@ static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t s * @brief Send a actuator_control_target message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -208,7 +208,7 @@ static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_ /** * @brief Get field time_usec from actuator_control_target message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) { @@ -218,7 +218,7 @@ static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const m /** * @brief Get field group_mlx from actuator_control_target message * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. */ static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) { @@ -228,7 +228,7 @@ static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const ma /** * @brief Get field controls from actuator_control_target message * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. */ static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) { diff --git a/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h b/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h index d395be5e9d..7296c22aa5 100755 --- a/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h +++ b/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h @@ -3,22 +3,22 @@ #define MAVLINK_MSG_ID_ADSB_VEHICLE 246 -MAVPACKED( + typedef struct __mavlink_adsb_vehicle_t { - uint32_t ICAO_address; /*< ICAO address*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t altitude; /*< Altitude(ASL) in millimeters*/ - uint16_t heading; /*< Course over ground in centidegrees*/ - uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/ - int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/ - uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/ - uint16_t squawk; /*< Squawk code*/ - uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/ - char callsign[9]; /*< The callsign, 8+null*/ - uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/ - uint8_t tslc; /*< Time since last communication in seconds*/ -}) mavlink_adsb_vehicle_t; + uint32_t ICAO_address; /*< ICAO address*/ + int32_t lat; /*< [degE7] Latitude*/ + int32_t lon; /*< [degE7] Longitude*/ + int32_t altitude; /*< [mm] Altitude(ASL)*/ + uint16_t heading; /*< [cdeg] Course over ground*/ + uint16_t hor_velocity; /*< [cm/s] The horizontal velocity*/ + int16_t ver_velocity; /*< [cm/s] The vertical velocity. Positive is up*/ + uint16_t flags; /*< Bitmap to indicate various statuses including valid data fields*/ + uint16_t squawk; /*< Squawk code*/ + uint8_t altitude_type; /*< ADSB altitude type.*/ + char callsign[9]; /*< The callsign, 8+null*/ + uint8_t emitter_type; /*< ADSB emitter type.*/ + uint8_t tslc; /*< [s] Time since last communication in seconds*/ +} mavlink_adsb_vehicle_t; #define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38 #define MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN 38 @@ -38,16 +38,16 @@ typedef struct __mavlink_adsb_vehicle_t { { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ + { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ + { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ } \ } #else @@ -57,16 +57,16 @@ typedef struct __mavlink_adsb_vehicle_t { { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ + { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ + { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ } \ } #endif @@ -77,19 +77,19 @@ typedef struct __mavlink_adsb_vehicle_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code + * @param ICAO_address ICAO address + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param altitude_type ADSB altitude type. + * @param altitude [mm] Altitude(ASL) + * @param heading [cdeg] Course over ground + * @param hor_velocity [cm/s] The horizontal velocity + * @param ver_velocity [cm/s] The vertical velocity. Positive is up + * @param callsign The callsign, 8+null + * @param emitter_type ADSB emitter type. + * @param tslc [s] Time since last communication in seconds + * @param flags Bitmap to indicate various statuses including valid data fields + * @param squawk Squawk code * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -139,19 +139,19 @@ static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code + * @param ICAO_address ICAO address + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param altitude_type ADSB altitude type. + * @param altitude [mm] Altitude(ASL) + * @param heading [cdeg] Course over ground + * @param hor_velocity [cm/s] The horizontal velocity + * @param ver_velocity [cm/s] The vertical velocity. Positive is up + * @param callsign The callsign, 8+null + * @param emitter_type ADSB emitter type. + * @param tslc [s] Time since last communication in seconds + * @param flags Bitmap to indicate various statuses including valid data fields + * @param squawk Squawk code * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -227,19 +227,19 @@ static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, u * @brief Send a adsb_vehicle message * @param chan MAVLink channel to send the message * - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code + * @param ICAO_address ICAO address + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param altitude_type ADSB altitude type. + * @param altitude [mm] Altitude(ASL) + * @param heading [cdeg] Course over ground + * @param hor_velocity [cm/s] The horizontal velocity + * @param ver_velocity [cm/s] The vertical velocity. Positive is up + * @param callsign The callsign, 8+null + * @param emitter_type ADSB emitter type. + * @param tslc [s] Time since last communication in seconds + * @param flags Bitmap to indicate various statuses including valid data fields + * @param squawk Squawk code */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -348,7 +348,7 @@ static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field ICAO_address from adsb_vehicle message * - * @return ICAO address + * @return ICAO address */ static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg) { @@ -358,7 +358,7 @@ static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_m /** * @brief Get field lat from adsb_vehicle message * - * @return Latitude, expressed as degrees * 1E7 + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg) { @@ -368,7 +368,7 @@ static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* /** * @brief Get field lon from adsb_vehicle message * - * @return Longitude, expressed as degrees * 1E7 + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg) { @@ -378,7 +378,7 @@ static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* /** * @brief Get field altitude_type from adsb_vehicle message * - * @return Type from ADSB_ALTITUDE_TYPE enum + * @return ADSB altitude type. */ static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg) { @@ -388,7 +388,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_m /** * @brief Get field altitude from adsb_vehicle message * - * @return Altitude(ASL) in millimeters + * @return [mm] Altitude(ASL) */ static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg) { @@ -398,7 +398,7 @@ static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_messag /** * @brief Get field heading from adsb_vehicle message * - * @return Course over ground in centidegrees + * @return [cdeg] Course over ground */ static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_messag /** * @brief Get field hor_velocity from adsb_vehicle message * - * @return The horizontal velocity in centimeters/second + * @return [cm/s] The horizontal velocity */ static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_m /** * @brief Get field ver_velocity from adsb_vehicle message * - * @return The vertical velocity in centimeters/second, positive is up + * @return [cm/s] The vertical velocity. Positive is up */ static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_me /** * @brief Get field callsign from adsb_vehicle message * - * @return The callsign, 8+null + * @return The callsign, 8+null */ static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign) { @@ -438,7 +438,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_messa /** * @brief Get field emitter_type from adsb_vehicle message * - * @return Type from ADSB_EMITTER_TYPE enum + * @return ADSB emitter type. */ static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg) { @@ -448,7 +448,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_me /** * @brief Get field tslc from adsb_vehicle message * - * @return Time since last communication in seconds + * @return [s] Time since last communication in seconds */ static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg) { @@ -458,7 +458,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* /** * @brief Get field flags from adsb_vehicle message * - * @return Flags to indicate various statuses including valid data fields + * @return Bitmap to indicate various statuses including valid data fields */ static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg) { @@ -468,7 +468,7 @@ static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_ /** * @brief Get field squawk from adsb_vehicle message * - * @return Squawk code + * @return Squawk code */ static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_altitude.h b/lib/main/MAVLink/common/mavlink_msg_altitude.h index d51a9e80c0..1424f0ab9d 100755 --- a/lib/main/MAVLink/common/mavlink_msg_altitude.h +++ b/lib/main/MAVLink/common/mavlink_msg_altitude.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_ALTITUDE 141 -MAVPACKED( + typedef struct __mavlink_altitude_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ - float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/ - float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ - float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/ - float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ - float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ -}) mavlink_altitude_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float altitude_monotonic; /*< [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ + float altitude_amsl; /*< [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.*/ + float altitude_local; /*< [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ + float altitude_relative; /*< [m] This is the altitude above the home position. It resets on each change of the current home position.*/ + float altitude_terrain; /*< [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ + float bottom_clearance; /*< [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ +} mavlink_altitude_t; #define MAVLINK_MSG_ID_ALTITUDE_LEN 32 #define MAVLINK_MSG_ID_ALTITUDE_MIN_LEN 32 @@ -59,13 +59,13 @@ typedef struct __mavlink_altitude_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. + * @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. + * @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8 * @brief Send a altitude message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. + * @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field time_usec from altitude message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_ /** * @brief Get field altitude_monotonic from altitude message * - * @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @return [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. */ static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_me /** * @brief Get field altitude_amsl from altitude message * - * @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @return [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. */ static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message /** * @brief Get field altitude_local from altitude message * - * @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @return [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. */ static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_messag /** * @brief Get field altitude_relative from altitude message * - * @return This is the altitude above the home position. It resets on each change of the current home position. + * @return [m] This is the altitude above the home position. It resets on each change of the current home position. */ static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_mes /** * @brief Get field altitude_terrain from altitude message * - * @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @return [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. */ static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_mess /** * @brief Get field bottom_clearance from altitude message * - * @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @return [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. */ static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_att_pos_mocap.h b/lib/main/MAVLink/common/mavlink_msg_att_pos_mocap.h index 3c1a251a6e..dab6f557b6 100755 --- a/lib/main/MAVLink/common/mavlink_msg_att_pos_mocap.h +++ b/lib/main/MAVLink/common/mavlink_msg_att_pos_mocap.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 -MAVPACKED( + typedef struct __mavlink_att_pos_mocap_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float x; /*< X position in meters (NED)*/ - float y; /*< Y position in meters (NED)*/ - float z; /*< Z position in meters (NED)*/ -}) mavlink_att_pos_mocap_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float x; /*< [m] X position (NED)*/ + float y; /*< [m] Y position (NED)*/ + float z; /*< [m] Z position (NED)*/ +} mavlink_att_pos_mocap_t; #define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36 @@ -53,11 +53,11 @@ typedef struct __mavlink_att_pos_mocap_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x [m] X position (NED) + * @param y [m] Y position (NED) + * @param z [m] Z position (NED) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x [m] X position (NED) + * @param y [m] Y position (NED) + * @param z [m] Z position (NED) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, * @brief Send a att_pos_mocap message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x [m] X position (NED) + * @param y [m] Y position (NED) + * @param z [m] Z position (NED) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field time_usec from att_pos_mocap message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) { @@ -246,7 +246,7 @@ static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_mes /** * @brief Get field q from att_pos_mocap message * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) */ static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) { @@ -256,7 +256,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* /** * @brief Get field x from att_pos_mocap message * - * @return X position in meters (NED) + * @return [m] X position (NED) */ static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) { @@ -266,7 +266,7 @@ static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg /** * @brief Get field y from att_pos_mocap message * - * @return Y position in meters (NED) + * @return [m] Y position (NED) */ static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg /** * @brief Get field z from att_pos_mocap message * - * @return Z position in meters (NED) + * @return [m] Z position (NED) */ static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_attitude.h b/lib/main/MAVLink/common/mavlink_msg_attitude.h index 21472fb2b0..6a8237c92c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_attitude.h +++ b/lib/main/MAVLink/common/mavlink_msg_attitude.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_ATTITUDE 30 -MAVPACKED( + typedef struct __mavlink_attitude_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float roll; /*< Roll angle (rad, -pi..+pi)*/ - float pitch; /*< Pitch angle (rad, -pi..+pi)*/ - float yaw; /*< Yaw angle (rad, -pi..+pi)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ -}) mavlink_attitude_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float roll; /*< [rad] Roll angle (-pi..+pi)*/ + float pitch; /*< [rad] Pitch angle (-pi..+pi)*/ + float yaw; /*< [rad] Yaw angle (-pi..+pi)*/ + float rollspeed; /*< [rad/s] Roll angular speed*/ + float pitchspeed; /*< [rad/s] Pitch angular speed*/ + float yawspeed; /*< [rad/s] Yaw angular speed*/ +} mavlink_attitude_t; #define MAVLINK_MSG_ID_ATTITUDE_LEN 28 #define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28 @@ -59,13 +59,13 @@ typedef struct __mavlink_attitude_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param roll [rad] Roll angle (-pi..+pi) + * @param pitch [rad] Pitch angle (-pi..+pi) + * @param yaw [rad] Yaw angle (-pi..+pi) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param roll [rad] Roll angle (-pi..+pi) + * @param pitch [rad] Pitch angle (-pi..+pi) + * @param yaw [rad] Yaw angle (-pi..+pi) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8 * @brief Send a attitude message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param roll [rad] Roll angle (-pi..+pi) + * @param pitch [rad] Pitch angle (-pi..+pi) + * @param yaw [rad] Yaw angle (-pi..+pi) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field time_boot_ms from attitude message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_messa /** * @brief Get field roll from attitude message * - * @return Roll angle (rad, -pi..+pi) + * @return [rad] Roll angle (-pi..+pi) */ static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) /** * @brief Get field pitch from attitude message * - * @return Pitch angle (rad, -pi..+pi) + * @return [rad] Pitch angle (-pi..+pi) */ static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) /** * @brief Get field yaw from attitude message * - * @return Yaw angle (rad, -pi..+pi) + * @return [rad] Yaw angle (-pi..+pi) */ static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) /** * @brief Get field rollspeed from attitude message * - * @return Roll angular speed (rad/s) + * @return [rad/s] Roll angular speed */ static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* /** * @brief Get field pitchspeed from attitude message * - * @return Pitch angular speed (rad/s) + * @return [rad/s] Pitch angular speed */ static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* /** * @brief Get field yawspeed from attitude message * - * @return Yaw angular speed (rad/s) + * @return [rad/s] Yaw angular speed */ static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion.h b/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion.h index df8e1e97a9..3ef53c4413 100755 --- a/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion.h +++ b/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion.h @@ -3,17 +3,17 @@ #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 -MAVPACKED( + typedef struct __mavlink_attitude_quaternion_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ -}) mavlink_attitude_quaternion_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ + float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ + float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ + float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ + float rollspeed; /*< [rad/s] Roll angular speed*/ + float pitchspeed; /*< [rad/s] Pitch angular speed*/ + float yawspeed; /*< [rad/s] Yaw angular speed*/ +} mavlink_attitude_quaternion_t; #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32 @@ -62,14 +62,14 @@ typedef struct __mavlink_attitude_quaternion_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t syste * @brief Send a attitude_quaternion message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -286,7 +286,7 @@ static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *m /** * @brief Get field time_boot_ms from attitude_quaternion message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) { @@ -296,7 +296,7 @@ static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const ma /** * @brief Get field q1 from attitude_quaternion message * - * @return Quaternion component 1, w (1 in null-rotation) + * @return Quaternion component 1, w (1 in null-rotation) */ static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) { @@ -306,7 +306,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message /** * @brief Get field q2 from attitude_quaternion message * - * @return Quaternion component 2, x (0 in null-rotation) + * @return Quaternion component 2, x (0 in null-rotation) */ static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message /** * @brief Get field q3 from attitude_quaternion message * - * @return Quaternion component 3, y (0 in null-rotation) + * @return Quaternion component 3, y (0 in null-rotation) */ static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message /** * @brief Get field q4 from attitude_quaternion message * - * @return Quaternion component 4, z (0 in null-rotation) + * @return Quaternion component 4, z (0 in null-rotation) */ static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message /** * @brief Get field rollspeed from attitude_quaternion message * - * @return Roll angular speed (rad/s) + * @return [rad/s] Roll angular speed */ static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_ /** * @brief Get field pitchspeed from attitude_quaternion message * - * @return Pitch angular speed (rad/s) + * @return [rad/s] Pitch angular speed */ static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink /** * @brief Get field yawspeed from attitude_quaternion message * - * @return Yaw angular speed (rad/s) + * @return [rad/s] Yaw angular speed */ static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion_cov.h b/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion_cov.h index adfcfa7905..bc2351aa3c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion_cov.h +++ b/lib/main/MAVLink/common/mavlink_msg_attitude_quaternion_cov.h @@ -3,15 +3,15 @@ #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61 -MAVPACKED( + typedef struct __mavlink_attitude_quaternion_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ - float covariance[9]; /*< Attitude covariance*/ -}) mavlink_attitude_quaternion_cov_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ + float rollspeed; /*< [rad/s] Roll angular speed*/ + float pitchspeed; /*< [rad/s] Pitch angular speed*/ + float yawspeed; /*< [rad/s] Yaw angular speed*/ + float covariance[9]; /*< Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/ +} mavlink_attitude_quaternion_cov_t; #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 72 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN 72 @@ -57,12 +57,12 @@ typedef struct __mavlink_attitude_quaternion_cov_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed + * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -98,12 +98,12 @@ static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_i * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed + * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -165,12 +165,12 @@ static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t s * @brief Send a attitude_quaternion_cov message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed [rad/s] Roll angular speed + * @param pitchspeed [rad/s] Pitch angular speed + * @param yawspeed [rad/s] Yaw angular speed + * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -251,7 +251,7 @@ static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_ /** * @brief Get field time_usec from attitude_quaternion_cov message * - * @return Timestamp (microseconds since system boot or since UNIX epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const mavlink_message_t* msg) { @@ -261,7 +261,7 @@ static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const m /** * @brief Get field q from attitude_quaternion_cov message * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) */ static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q) { @@ -271,7 +271,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_m /** * @brief Get field rollspeed from attitude_quaternion_cov message * - * @return Roll angular speed (rad/s) + * @return [rad/s] Roll angular speed */ static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg) { @@ -281,7 +281,7 @@ static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavl /** * @brief Get field pitchspeed from attitude_quaternion_cov message * - * @return Pitch angular speed (rad/s) + * @return [rad/s] Pitch angular speed */ static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg) { @@ -291,7 +291,7 @@ static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mav /** * @brief Get field yawspeed from attitude_quaternion_cov message * - * @return Yaw angular speed (rad/s) + * @return [rad/s] Yaw angular speed */ static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg) { @@ -301,7 +301,7 @@ static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavli /** * @brief Get field covariance from attitude_quaternion_cov message * - * @return Attitude covariance + * @return Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. */ static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance) { diff --git a/lib/main/MAVLink/common/mavlink_msg_attitude_target.h b/lib/main/MAVLink/common/mavlink_msg_attitude_target.h index 74c98f0f6a..af578884f4 100755 --- a/lib/main/MAVLink/common/mavlink_msg_attitude_target.h +++ b/lib/main/MAVLink/common/mavlink_msg_attitude_target.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 -MAVPACKED( + typedef struct __mavlink_attitude_target_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< Body roll rate in radians per second*/ - float body_pitch_rate; /*< Body roll rate in radians per second*/ - float body_yaw_rate; /*< Body roll rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/ -}) mavlink_attitude_target_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float body_roll_rate; /*< [rad/s] Body roll rate*/ + float body_pitch_rate; /*< [rad/s] Body pitch rate*/ + float body_yaw_rate; /*< [rad/s] Body yaw rate*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ + uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/ +} mavlink_attitude_target_t; #define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 #define MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN 37 @@ -30,12 +30,12 @@ typedef struct __mavlink_attitude_target_t { "ATTITUDE_TARGET", \ 7, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ } \ } #else @@ -43,12 +43,12 @@ typedef struct __mavlink_attitude_target_t { "ATTITUDE_TARGET", \ 7, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ } \ } #endif @@ -59,13 +59,13 @@ typedef struct __mavlink_attitude_target_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate [rad/s] Body roll rate + * @param body_pitch_rate [rad/s] Body pitch rate + * @param body_yaw_rate [rad/s] Body yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -103,13 +103,13 @@ static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate [rad/s] Body roll rate + * @param body_pitch_rate [rad/s] Body pitch rate + * @param body_yaw_rate [rad/s] Body yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -173,13 +173,13 @@ static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id * @brief Send a attitude_target message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate [rad/s] Body roll rate + * @param body_pitch_rate [rad/s] Body pitch rate + * @param body_yaw_rate [rad/s] Body yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -264,7 +264,7 @@ static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbu /** * @brief Get field time_boot_ms from attitude_target message * - * @return Timestamp in milliseconds since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) { @@ -274,7 +274,7 @@ static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlin /** * @brief Get field type_mask from attitude_target message * - * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude */ static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg) { @@ -284,7 +284,7 @@ static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_me /** * @brief Get field q from attitude_target message * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) */ static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q) { @@ -294,7 +294,7 @@ static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t /** * @brief Get field body_roll_rate from attitude_target message * - * @return Body roll rate in radians per second + * @return [rad/s] Body roll rate */ static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) { @@ -304,7 +304,7 @@ static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink /** * @brief Get field body_pitch_rate from attitude_target message * - * @return Body roll rate in radians per second + * @return [rad/s] Body pitch rate */ static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) { @@ -314,7 +314,7 @@ static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlin /** * @brief Get field body_yaw_rate from attitude_target message * - * @return Body roll rate in radians per second + * @return [rad/s] Body yaw rate */ static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_ /** * @brief Get field thrust from attitude_target message * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) */ static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_auth_key.h b/lib/main/MAVLink/common/mavlink_msg_auth_key.h index 2754a2ad6b..57cd6916ab 100755 --- a/lib/main/MAVLink/common/mavlink_msg_auth_key.h +++ b/lib/main/MAVLink/common/mavlink_msg_auth_key.h @@ -3,10 +3,10 @@ #define MAVLINK_MSG_ID_AUTH_KEY 7 -MAVPACKED( + typedef struct __mavlink_auth_key_t { - char key[32]; /*< key*/ -}) mavlink_auth_key_t; + char key[32]; /*< key*/ +} mavlink_auth_key_t; #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 #define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32 @@ -41,7 +41,7 @@ typedef struct __mavlink_auth_key_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param key key + * @param key key * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param key key + * @param key key * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -123,7 +123,7 @@ static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8 * @brief Send a auth_key message * @param chan MAVLink channel to send the message * - * @param key key + * @param key key */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -188,7 +188,7 @@ static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field key from auth_key message * - * @return key + * @return key */ static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) { diff --git a/lib/main/MAVLink/common/mavlink_msg_autopilot_version.h b/lib/main/MAVLink/common/mavlink_msg_autopilot_version.h index 68f7d83b69..ae0324b75b 100755 --- a/lib/main/MAVLink/common/mavlink_msg_autopilot_version.h +++ b/lib/main/MAVLink/common/mavlink_msg_autopilot_version.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 -MAVPACKED( + typedef struct __mavlink_autopilot_version_t { - uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/ - uint64_t uid; /*< UID if provided by hardware*/ - uint32_t flight_sw_version; /*< Firmware version number*/ - uint32_t middleware_sw_version; /*< Middleware version number*/ - uint32_t os_sw_version; /*< Operating system version number*/ - uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/ - uint16_t vendor_id; /*< ID of the board vendor*/ - uint16_t product_id; /*< ID of the product*/ - uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ -}) mavlink_autopilot_version_t; + uint64_t capabilities; /*< Bitmap of capabilities*/ + uint64_t uid; /*< UID if provided by hardware (see uid2)*/ + uint32_t flight_sw_version; /*< Firmware version number*/ + uint32_t middleware_sw_version; /*< Middleware version number*/ + uint32_t os_sw_version; /*< Operating system version number*/ + uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/ + uint16_t vendor_id; /*< ID of the board vendor*/ + uint16_t product_id; /*< ID of the product*/ + uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ + uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ + uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ +} mavlink_autopilot_version_t; #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60 @@ -36,16 +36,16 @@ typedef struct __mavlink_autopilot_version_t { "AUTOPILOT_VERSION", \ 11, \ { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ + { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ + { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ + { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ } \ } #else @@ -53,16 +53,16 @@ typedef struct __mavlink_autopilot_version_t { "AUTOPILOT_VERSION", \ 11, \ { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ + { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ + { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ + { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ } \ } #endif @@ -73,17 +73,17 @@ typedef struct __mavlink_autopilot_version_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware + * @param capabilities Bitmap of capabilities + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware (see uid2) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -129,17 +129,17 @@ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware + * @param capabilities Bitmap of capabilities + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware (see uid2) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -211,17 +211,17 @@ static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_ * @brief Send a autopilot_version message * @param chan MAVLink channel to send the message * - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware + * @param capabilities Bitmap of capabilities + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware (see uid2) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -322,7 +322,7 @@ static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msg /** * @brief Get field capabilities from autopilot_version message * - * @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @return Bitmap of capabilities */ static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavl /** * @brief Get field flight_sw_version from autopilot_version message * - * @return Firmware version number + * @return Firmware version number */ static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg) { @@ -342,7 +342,7 @@ static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const /** * @brief Get field middleware_sw_version from autopilot_version message * - * @return Middleware version number + * @return Middleware version number */ static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(c /** * @brief Get field os_sw_version from autopilot_version message * - * @return Operating system version number + * @return Operating system version number */ static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mav /** * @brief Get field board_version from autopilot_version message * - * @return HW / board version (last 8 bytes should be silicon ID, if any) + * @return HW / board version (last 8 bytes should be silicon ID, if any) */ static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mav /** * @brief Get field flight_custom_version from autopilot_version message * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. */ static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version) { @@ -382,7 +382,7 @@ static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(c /** * @brief Get field middleware_custom_version from autopilot_version message * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. */ static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version) { @@ -392,7 +392,7 @@ static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_versi /** * @brief Get field os_custom_version from autopilot_version message * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. */ static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version) { @@ -402,7 +402,7 @@ static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const /** * @brief Get field vendor_id from autopilot_version message * - * @return ID of the board vendor + * @return ID of the board vendor */ static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg) { @@ -412,7 +412,7 @@ static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink /** * @brief Get field product_id from autopilot_version message * - * @return ID of the product + * @return ID of the product */ static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg) { @@ -422,7 +422,7 @@ static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlin /** * @brief Get field uid from autopilot_version message * - * @return UID if provided by hardware + * @return UID if provided by hardware (see uid2) */ static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_battery_status.h b/lib/main/MAVLink/common/mavlink_msg_battery_status.h index 240463aba8..9d5ac516b2 100755 --- a/lib/main/MAVLink/common/mavlink_msg_battery_status.h +++ b/lib/main/MAVLink/common/mavlink_msg_battery_status.h @@ -3,18 +3,18 @@ #define MAVLINK_MSG_ID_BATTERY_STATUS 147 -MAVPACKED( + typedef struct __mavlink_battery_status_t { - int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/ - int32_t energy_consumed; /*< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/ - int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/ - uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/ - int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ - uint8_t id; /*< Battery ID*/ - uint8_t battery_function; /*< Function of the battery*/ - uint8_t type; /*< Type (chemistry) of the battery*/ - int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/ -}) mavlink_battery_status_t; + int32_t current_consumed; /*< [mAh] Consumed charge, -1: autopilot does not provide consumption estimate*/ + int32_t energy_consumed; /*< [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate*/ + int16_t temperature; /*< [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.*/ + uint16_t voltages[10]; /*< [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).*/ + int16_t current_battery; /*< [cA] Battery current, -1: autopilot does not measure the current*/ + uint8_t id; /*< Battery ID*/ + uint8_t battery_function; /*< Function of the battery*/ + uint8_t type; /*< Type (chemistry) of the battery*/ + int8_t battery_remaining; /*< [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.*/ +} mavlink_battery_status_t; #define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 #define MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN 36 @@ -31,14 +31,14 @@ typedef struct __mavlink_battery_status_t { 147, \ "BATTERY_STATUS", \ 9, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ + { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ + { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ + { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ + { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ } \ } @@ -46,14 +46,14 @@ typedef struct __mavlink_battery_status_t { #define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ "BATTERY_STATUS", \ 9, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ + { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ + { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ + { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ + { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ } \ } @@ -65,15 +65,15 @@ typedef struct __mavlink_battery_status_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. + * @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). + * @param current_battery [cA] Battery current, -1: autopilot does not measure the current + * @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate + * @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate + * @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -115,15 +115,15 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. + * @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). + * @param current_battery [cA] Battery current, -1: autopilot does not measure the current + * @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate + * @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate + * @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -191,15 +191,15 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, * @brief Send a battery_status message * @param chan MAVLink channel to send the message * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. + * @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). + * @param current_battery [cA] Battery current, -1: autopilot does not measure the current + * @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate + * @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate + * @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -292,7 +292,7 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf /** * @brief Get field id from battery_status message * - * @return Battery ID + * @return Battery ID */ static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* /** * @brief Get field battery_function from battery_status message * - * @return Function of the battery + * @return Function of the battery */ static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavl /** * @brief Get field type from battery_status message * - * @return Type (chemistry) of the battery + * @return Type (chemistry) of the battery */ static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_ /** * @brief Get field temperature from battery_status message * - * @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @return [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. */ static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_m /** * @brief Get field voltages from battery_status message * - * @return Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @return [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). */ static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages) { @@ -342,7 +342,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_mes /** * @brief Get field current_battery from battery_status message * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @return [cA] Battery current, -1: autopilot does not measure the current */ static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavli /** * @brief Get field current_consumed from battery_status message * - * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @return [mAh] Consumed charge, -1: autopilot does not provide consumption estimate */ static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavl /** * @brief Get field energy_consumed from battery_status message * - * @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @return [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate */ static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavli /** * @brief Get field battery_remaining from battery_status message * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @return [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. */ static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_camera_trigger.h b/lib/main/MAVLink/common/mavlink_msg_camera_trigger.h index 71bb1c1c86..ee2ad8e9b0 100755 --- a/lib/main/MAVLink/common/mavlink_msg_camera_trigger.h +++ b/lib/main/MAVLink/common/mavlink_msg_camera_trigger.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_CAMERA_TRIGGER 112 -MAVPACKED( + typedef struct __mavlink_camera_trigger_t { - uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/ - uint32_t seq; /*< Image frame sequence*/ -}) mavlink_camera_trigger_t; + uint64_t time_usec; /*< [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint32_t seq; /*< Image frame sequence*/ +} mavlink_camera_trigger_t; #define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12 #define MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN 12 @@ -44,8 +44,8 @@ typedef struct __mavlink_camera_trigger_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence + * @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param seq Image frame sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence + * @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param seq Image frame sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, * @brief Send a camera_trigger message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence + * @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param seq Image frame sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf /** * @brief Get field time_usec from camera_trigger message * - * @return Timestamp for the image frame in microseconds + * @return [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_me /** * @brief Get field seq from camera_trigger message * - * @return Image frame sequence + * @return Image frame sequence */ static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h b/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h index b6e76f7f7a..8fea8d7837 100755 --- a/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h +++ b/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 -MAVPACKED( + typedef struct __mavlink_change_operator_control_t { - uint8_t target_system; /*< System the GCS requests control for*/ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ - char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ -}) mavlink_change_operator_control_t; + uint8_t target_system; /*< System the GCS requests control for*/ + uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ + uint8_t version; /*< [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ + char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ +} mavlink_change_operator_control_t; #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN 28 @@ -50,10 +50,10 @@ typedef struct __mavlink_change_operator_control_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t s * @brief Send a change_operator_control message * @param chan MAVLink channel to send the message * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_ /** * @brief Get field target_system from change_operator_control message * - * @return System the GCS requests control for + * @return System the GCS requests control for */ static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_target_system(cons /** * @brief Get field control_request from change_operator_control message * - * @return 0: request control of this MAV, 1: Release control of this MAV + * @return 0: request control of this MAV, 1: Release control of this MAV */ static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) { @@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_control_request(co /** * @brief Get field version from change_operator_control message * - * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @return [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. */ static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) { @@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavl /** * @brief Get field passkey from change_operator_control message * - * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" */ static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) { diff --git a/lib/main/MAVLink/common/mavlink_msg_change_operator_control_ack.h b/lib/main/MAVLink/common/mavlink_msg_change_operator_control_ack.h index 16bcec880b..d35d444ba3 100755 --- a/lib/main/MAVLink/common/mavlink_msg_change_operator_control_ack.h +++ b/lib/main/MAVLink/common/mavlink_msg_change_operator_control_ack.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 -MAVPACKED( + typedef struct __mavlink_change_operator_control_ack_t { - uint8_t gcs_system_id; /*< ID of the GCS this message */ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ -}) mavlink_change_operator_control_ack_t; + uint8_t gcs_system_id; /*< ID of the GCS this message */ + uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ + uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ +} mavlink_change_operator_control_ack_t; #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN 3 @@ -47,9 +47,9 @@ typedef struct __mavlink_change_operator_control_ack_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t syst * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8 * @brief Send a change_operator_control_ack message * @param chan MAVLink channel to send the message * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_mess /** * @brief Get field gcs_system_id from change_operator_control_ack message * - * @return ID of the GCS this message + * @return ID of the GCS this message */ static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id( /** * @brief Get field control_request from change_operator_control_ack message * - * @return 0: request control of this MAV, 1: Release control of this MAV + * @return 0: request control of this MAV, 1: Release control of this MAV */ static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_reques /** * @brief Get field ack from change_operator_control_ack message * - * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control */ static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_collision.h b/lib/main/MAVLink/common/mavlink_msg_collision.h index b888c20a24..b7d8a07f25 100755 --- a/lib/main/MAVLink/common/mavlink_msg_collision.h +++ b/lib/main/MAVLink/common/mavlink_msg_collision.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_COLLISION 247 -MAVPACKED( + typedef struct __mavlink_collision_t { - uint32_t id; /*< Unique identifier, domain based on src field*/ - float time_to_minimum_delta; /*< Estimated time until collision occurs (seconds)*/ - float altitude_minimum_delta; /*< Closest vertical distance in meters between vehicle and object*/ - float horizontal_minimum_delta; /*< Closest horizontal distance in meteres between vehicle and object*/ - uint8_t src; /*< Collision data source*/ - uint8_t action; /*< Action that is being taken to avoid this collision*/ - uint8_t threat_level; /*< How concerned the aircraft is about this collision*/ -}) mavlink_collision_t; + uint32_t id; /*< Unique identifier, domain based on src field*/ + float time_to_minimum_delta; /*< [s] Estimated time until collision occurs*/ + float altitude_minimum_delta; /*< [m] Closest vertical distance between vehicle and object*/ + float horizontal_minimum_delta; /*< [m] Closest horizontal distance between vehicle and object*/ + uint8_t src; /*< Collision data source*/ + uint8_t action; /*< Action that is being taken to avoid this collision*/ + uint8_t threat_level; /*< How concerned the aircraft is about this collision*/ +} mavlink_collision_t; #define MAVLINK_MSG_ID_COLLISION_LEN 19 #define MAVLINK_MSG_ID_COLLISION_MIN_LEN 19 @@ -29,26 +29,26 @@ typedef struct __mavlink_collision_t { 247, \ "COLLISION", \ 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ + { { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ + { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ + { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ + { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_COLLISION { \ "COLLISION", \ 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ + { { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ + { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ + { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ + { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ } \ } #endif @@ -59,13 +59,13 @@ typedef struct __mavlink_collision_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object + * @param src Collision data source + * @param id Unique identifier, domain based on src field + * @param action Action that is being taken to avoid this collision + * @param threat_level How concerned the aircraft is about this collision + * @param time_to_minimum_delta [s] Estimated time until collision occurs + * @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object + * @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object + * @param src Collision data source + * @param id Unique identifier, domain based on src field + * @param action Action that is being taken to avoid this collision + * @param threat_level How concerned the aircraft is about this collision + * @param time_to_minimum_delta [s] Estimated time until collision occurs + * @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object + * @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_collision_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_collision_encode_chan(uint8_t system_id, uint * @brief Send a collision message * @param chan MAVLink channel to send the message * - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object + * @param src Collision data source + * @param id Unique identifier, domain based on src field + * @param action Action that is being taken to avoid this collision + * @param threat_level How concerned the aircraft is about this collision + * @param time_to_minimum_delta [s] Estimated time until collision occurs + * @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object + * @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_collision_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field src from collision message * - * @return Collision data source + * @return Collision data source */ static inline uint8_t mavlink_msg_collision_get_src(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint8_t mavlink_msg_collision_get_src(const mavlink_message_t* msg /** * @brief Get field id from collision message * - * @return Unique identifier, domain based on src field + * @return Unique identifier, domain based on src field */ static inline uint32_t mavlink_msg_collision_get_id(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline uint32_t mavlink_msg_collision_get_id(const mavlink_message_t* msg /** * @brief Get field action from collision message * - * @return Action that is being taken to avoid this collision + * @return Action that is being taken to avoid this collision */ static inline uint8_t mavlink_msg_collision_get_action(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint8_t mavlink_msg_collision_get_action(const mavlink_message_t* /** * @brief Get field threat_level from collision message * - * @return How concerned the aircraft is about this collision + * @return How concerned the aircraft is about this collision */ static inline uint8_t mavlink_msg_collision_get_threat_level(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline uint8_t mavlink_msg_collision_get_threat_level(const mavlink_messa /** * @brief Get field time_to_minimum_delta from collision message * - * @return Estimated time until collision occurs (seconds) + * @return [s] Estimated time until collision occurs */ static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlin /** * @brief Get field altitude_minimum_delta from collision message * - * @return Closest vertical distance in meters between vehicle and object + * @return [m] Closest vertical distance between vehicle and object */ static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavli /** * @brief Get field horizontal_minimum_delta from collision message * - * @return Closest horizontal distance in meteres between vehicle and object + * @return [m] Closest horizontal distance between vehicle and object */ static inline float mavlink_msg_collision_get_horizontal_minimum_delta(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_command_ack.h b/lib/main/MAVLink/common/mavlink_msg_command_ack.h index 7ace685119..52991543c5 100755 --- a/lib/main/MAVLink/common/mavlink_msg_command_ack.h +++ b/lib/main/MAVLink/common/mavlink_msg_command_ack.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_COMMAND_ACK 77 -MAVPACKED( + typedef struct __mavlink_command_ack_t { - uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ - uint8_t result; /*< See MAV_RESULT enum*/ -}) mavlink_command_ack_t; + uint16_t command; /*< Command ID (of acknowledged command).*/ + uint8_t result; /*< Result of command.*/ +} mavlink_command_ack_t; #define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 #define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3 @@ -44,8 +44,8 @@ typedef struct __mavlink_command_ack_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum + * @param command Command ID (of acknowledged command). + * @param result Result of command. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum + * @param command Command ID (of acknowledged command). + * @param result Result of command. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, ui * @brief Send a command_ack message * @param chan MAVLink channel to send the message * - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum + * @param command Command ID (of acknowledged command). + * @param result Result of command. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field command from command_ack message * - * @return Command ID, as defined by MAV_CMD enum. + * @return Command ID (of acknowledged command). */ static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message /** * @brief Get field result from command_ack message * - * @return See MAV_RESULT enum + * @return Result of command. */ static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_command_cancel.h b/lib/main/MAVLink/common/mavlink_msg_command_cancel.h new file mode 100644 index 0000000000..0ad7dac584 --- /dev/null +++ b/lib/main/MAVLink/common/mavlink_msg_command_cancel.h @@ -0,0 +1,263 @@ +#pragma once +// MESSAGE COMMAND_CANCEL PACKING + +#define MAVLINK_MSG_ID_COMMAND_CANCEL 80 + + +typedef struct __mavlink_command_cancel_t { + uint16_t command; /*< Command ID (of command to cancel).*/ + uint8_t target_system; /*< System executing long running command. Should not be broadcast (0).*/ + uint8_t target_component; /*< Component executing long running command.*/ +} mavlink_command_cancel_t; + +#define MAVLINK_MSG_ID_COMMAND_CANCEL_LEN 4 +#define MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN 4 +#define MAVLINK_MSG_ID_80_LEN 4 +#define MAVLINK_MSG_ID_80_MIN_LEN 4 + +#define MAVLINK_MSG_ID_COMMAND_CANCEL_CRC 14 +#define MAVLINK_MSG_ID_80_CRC 14 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_COMMAND_CANCEL { \ + 80, \ + "COMMAND_CANCEL", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_cancel_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_cancel_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_cancel_t, command) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_COMMAND_CANCEL { \ + "COMMAND_CANCEL", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_cancel_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_cancel_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_cancel_t, command) }, \ + } \ +} +#endif + +/** + * @brief Pack a command_cancel message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System executing long running command. Should not be broadcast (0). + * @param target_component Component executing long running command. + * @param command Command ID (of command to cancel). + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_cancel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); +#else + mavlink_command_cancel_t packet; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_CANCEL; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +} + +/** + * @brief Pack a command_cancel message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System executing long running command. Should not be broadcast (0). + * @param target_component Component executing long running command. + * @param command Command ID (of command to cancel). + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_cancel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); +#else + mavlink_command_cancel_t packet; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_CANCEL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +} + +/** + * @brief Encode a command_cancel struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_cancel C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_cancel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_cancel_t* command_cancel) +{ + return mavlink_msg_command_cancel_pack(system_id, component_id, msg, command_cancel->target_system, command_cancel->target_component, command_cancel->command); +} + +/** + * @brief Encode a command_cancel struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_cancel C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_cancel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_cancel_t* command_cancel) +{ + return mavlink_msg_command_cancel_pack_chan(system_id, component_id, chan, msg, command_cancel->target_system, command_cancel->target_component, command_cancel->command); +} + +/** + * @brief Send a command_cancel message + * @param chan MAVLink channel to send the message + * + * @param target_system System executing long running command. Should not be broadcast (0). + * @param target_component Component executing long running command. + * @param command Command ID (of command to cancel). + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_cancel_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, buf, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +#else + mavlink_command_cancel_t packet; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +#endif +} + +/** + * @brief Send a command_cancel message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_command_cancel_send_struct(mavlink_channel_t chan, const mavlink_command_cancel_t* command_cancel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_command_cancel_send(chan, command_cancel->target_system, command_cancel->target_component, command_cancel->command); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)command_cancel, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_CANCEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_cancel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, buf, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +#else + mavlink_command_cancel_t *packet = (mavlink_command_cancel_t *)msgbuf; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)packet, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_CANCEL UNPACKING + + +/** + * @brief Get field target_system from command_cancel message + * + * @return System executing long running command. Should not be broadcast (0). + */ +static inline uint8_t mavlink_msg_command_cancel_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from command_cancel message + * + * @return Component executing long running command. + */ +static inline uint8_t mavlink_msg_command_cancel_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field command from command_cancel message + * + * @return Command ID (of command to cancel). + */ +static inline uint16_t mavlink_msg_command_cancel_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a command_cancel message into a struct + * + * @param msg The message to decode + * @param command_cancel C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_cancel_decode(const mavlink_message_t* msg, mavlink_command_cancel_t* command_cancel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + command_cancel->command = mavlink_msg_command_cancel_get_command(msg); + command_cancel->target_system = mavlink_msg_command_cancel_get_target_system(msg); + command_cancel->target_component = mavlink_msg_command_cancel_get_target_component(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_CANCEL_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_CANCEL_LEN; + memset(command_cancel, 0, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); + memcpy(command_cancel, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/lib/main/MAVLink/common/mavlink_msg_command_int.h b/lib/main/MAVLink/common/mavlink_msg_command_int.h index 763634642e..dcd298a1c9 100755 --- a/lib/main/MAVLink/common/mavlink_msg_command_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_command_int.h @@ -3,22 +3,22 @@ #define MAVLINK_MSG_ID_COMMAND_INT 75 -MAVPACKED( + typedef struct __mavlink_command_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_command_int_t; + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ + int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ + float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).*/ + uint16_t command; /*< The scheduled action for the mission item.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the COMMAND.*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_command_int_t; #define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 #define MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN 35 @@ -35,38 +35,38 @@ typedef struct __mavlink_command_int_t { 75, \ "COMMAND_INT", \ 13, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ "COMMAND_INT", \ 13, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ } \ } #endif @@ -77,19 +77,19 @@ typedef struct __mavlink_command_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. + * @param command The scheduled action for the mission item. + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -141,19 +141,19 @@ static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. + * @param command The scheduled action for the mission item. + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -231,19 +231,19 @@ static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, ui * @brief Send a command_int message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. + * @param command The scheduled action for the mission item. + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -356,7 +356,7 @@ static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field target_system from command_int message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_me /** * @brief Get field target_component from command_int message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg) { @@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink /** * @brief Get field frame from command_int message * - * @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @return The coordinate system of the COMMAND. */ static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* /** * @brief Get field command from command_int message * - * @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @return The scheduled action for the mission item. */ static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message /** * @brief Get field current from command_int message * - * @return false:0, true:1 + * @return false:0, true:1 */ static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg) { @@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_ /** * @brief Get field autocontinue from command_int message * - * @return autocontinue to next wp + * @return autocontinue to next wp */ static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg) { @@ -416,7 +416,7 @@ static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_mes /** * @brief Get field param1 from command_int message * - * @return PARAM1, see MAV_CMD enum + * @return PARAM1, see MAV_CMD enum */ static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg) { @@ -426,7 +426,7 @@ static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* /** * @brief Get field param2 from command_int message * - * @return PARAM2, see MAV_CMD enum + * @return PARAM2, see MAV_CMD enum */ static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* /** * @brief Get field param3 from command_int message * - * @return PARAM3, see MAV_CMD enum + * @return PARAM3, see MAV_CMD enum */ static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* /** * @brief Get field param4 from command_int message * - * @return PARAM4, see MAV_CMD enum + * @return PARAM4, see MAV_CMD enum */ static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* /** * @brief Get field x from command_int message * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 */ static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg /** * @brief Get field y from command_int message * - * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 */ static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg /** * @brief Get field z from command_int message * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). */ static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_command_long.h b/lib/main/MAVLink/common/mavlink_msg_command_long.h index f7c62cb352..6a9a169875 100755 --- a/lib/main/MAVLink/common/mavlink_msg_command_long.h +++ b/lib/main/MAVLink/common/mavlink_msg_command_long.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_COMMAND_LONG 76 -MAVPACKED( + typedef struct __mavlink_command_long_t { - float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/ - float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/ - float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/ - float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/ - float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/ - float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/ - float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/ - uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ - uint8_t target_system; /*< System which should execute the command*/ - uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ - uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ -}) mavlink_command_long_t; + float param1; /*< Parameter 1 (for the specific command).*/ + float param2; /*< Parameter 2 (for the specific command).*/ + float param3; /*< Parameter 3 (for the specific command).*/ + float param4; /*< Parameter 4 (for the specific command).*/ + float param5; /*< Parameter 5 (for the specific command).*/ + float param6; /*< Parameter 6 (for the specific command).*/ + float param7; /*< Parameter 7 (for the specific command).*/ + uint16_t command; /*< Command ID (of command to send).*/ + uint8_t target_system; /*< System which should execute the command*/ + uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ + uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ +} mavlink_command_long_t; #define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 #define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33 @@ -33,34 +33,34 @@ typedef struct __mavlink_command_long_t { 76, \ "COMMAND_LONG", \ 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ "COMMAND_LONG", \ 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ } \ } #endif @@ -71,17 +71,17 @@ typedef struct __mavlink_command_long_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID (of command to send). + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1 (for the specific command). + * @param param2 Parameter 2 (for the specific command). + * @param param3 Parameter 3 (for the specific command). + * @param param4 Parameter 4 (for the specific command). + * @param param5 Parameter 5 (for the specific command). + * @param param6 Parameter 6 (for the specific command). + * @param param7 Parameter 7 (for the specific command). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -129,17 +129,17 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID (of command to send). + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1 (for the specific command). + * @param param2 Parameter 2 (for the specific command). + * @param param3 Parameter 3 (for the specific command). + * @param param4 Parameter 4 (for the specific command). + * @param param5 Parameter 5 (for the specific command). + * @param param6 Parameter 6 (for the specific command). + * @param param7 Parameter 7 (for the specific command). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -213,17 +213,17 @@ static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, u * @brief Send a command_long message * @param chan MAVLink channel to send the message * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID (of command to send). + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1 (for the specific command). + * @param param2 Parameter 2 (for the specific command). + * @param param3 Parameter 3 (for the specific command). + * @param param4 Parameter 4 (for the specific command). + * @param param5 Parameter 5 (for the specific command). + * @param param6 Parameter 6 (for the specific command). + * @param param7 Parameter 7 (for the specific command). */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -328,7 +328,7 @@ static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field target_system from command_long message * - * @return System which should execute the command + * @return System which should execute the command */ static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) { @@ -338,7 +338,7 @@ static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_m /** * @brief Get field target_component from command_long message * - * @return Component which should execute the command, 0 for all components + * @return Component which should execute the command, 0 for all components */ static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) { @@ -348,7 +348,7 @@ static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlin /** * @brief Get field command from command_long message * - * @return Command ID, as defined by MAV_CMD enum. + * @return Command ID (of command to send). */ static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) { @@ -358,7 +358,7 @@ static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_messag /** * @brief Get field confirmation from command_long message * - * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) */ static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) { @@ -368,7 +368,7 @@ static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_me /** * @brief Get field param1 from command_long message * - * @return Parameter 1, as defined by MAV_CMD enum. + * @return Parameter 1 (for the specific command). */ static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) { @@ -378,7 +378,7 @@ static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* /** * @brief Get field param2 from command_long message * - * @return Parameter 2, as defined by MAV_CMD enum. + * @return Parameter 2 (for the specific command). */ static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) { @@ -388,7 +388,7 @@ static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* /** * @brief Get field param3 from command_long message * - * @return Parameter 3, as defined by MAV_CMD enum. + * @return Parameter 3 (for the specific command). */ static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) { @@ -398,7 +398,7 @@ static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* /** * @brief Get field param4 from command_long message * - * @return Parameter 4, as defined by MAV_CMD enum. + * @return Parameter 4 (for the specific command). */ static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* /** * @brief Get field param5 from command_long message * - * @return Parameter 5, as defined by MAV_CMD enum. + * @return Parameter 5 (for the specific command). */ static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* /** * @brief Get field param6 from command_long message * - * @return Parameter 6, as defined by MAV_CMD enum. + * @return Parameter 6 (for the specific command). */ static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* /** * @brief Get field param7 from command_long message * - * @return Parameter 7, as defined by MAV_CMD enum. + * @return Parameter 7 (for the specific command). */ static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_control_system_state.h b/lib/main/MAVLink/common/mavlink_msg_control_system_state.h index 8914b6ae10..b4381cff4e 100755 --- a/lib/main/MAVLink/common/mavlink_msg_control_system_state.h +++ b/lib/main/MAVLink/common/mavlink_msg_control_system_state.h @@ -3,26 +3,26 @@ #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 -MAVPACKED( + typedef struct __mavlink_control_system_state_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float x_acc; /*< X acceleration in body frame*/ - float y_acc; /*< Y acceleration in body frame*/ - float z_acc; /*< Z acceleration in body frame*/ - float x_vel; /*< X velocity in body frame*/ - float y_vel; /*< Y velocity in body frame*/ - float z_vel; /*< Z velocity in body frame*/ - float x_pos; /*< X position in local frame*/ - float y_pos; /*< Y position in local frame*/ - float z_pos; /*< Z position in local frame*/ - float airspeed; /*< Airspeed, set to -1 if unknown*/ - float vel_variance[3]; /*< Variance of body velocity estimate*/ - float pos_variance[3]; /*< Variance in local position*/ - float q[4]; /*< The attitude, represented as Quaternion*/ - float roll_rate; /*< Angular rate in roll axis*/ - float pitch_rate; /*< Angular rate in pitch axis*/ - float yaw_rate; /*< Angular rate in yaw axis*/ -}) mavlink_control_system_state_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float x_acc; /*< [m/s/s] X acceleration in body frame*/ + float y_acc; /*< [m/s/s] Y acceleration in body frame*/ + float z_acc; /*< [m/s/s] Z acceleration in body frame*/ + float x_vel; /*< [m/s] X velocity in body frame*/ + float y_vel; /*< [m/s] Y velocity in body frame*/ + float z_vel; /*< [m/s] Z velocity in body frame*/ + float x_pos; /*< [m] X position in local frame*/ + float y_pos; /*< [m] Y position in local frame*/ + float z_pos; /*< [m] Z position in local frame*/ + float airspeed; /*< [m/s] Airspeed, set to -1 if unknown*/ + float vel_variance[3]; /*< Variance of body velocity estimate*/ + float pos_variance[3]; /*< Variance in local position*/ + float q[4]; /*< The attitude, represented as Quaternion*/ + float roll_rate; /*< [rad/s] Angular rate in roll axis*/ + float pitch_rate; /*< [rad/s] Angular rate in pitch axis*/ + float yaw_rate; /*< [rad/s] Angular rate in yaw axis*/ +} mavlink_control_system_state_t; #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100 @@ -91,23 +91,23 @@ typedef struct __mavlink_control_system_state_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param x_acc [m/s/s] X acceleration in body frame + * @param y_acc [m/s/s] Y acceleration in body frame + * @param z_acc [m/s/s] Z acceleration in body frame + * @param x_vel [m/s] X velocity in body frame + * @param y_vel [m/s] Y velocity in body frame + * @param z_vel [m/s] Z velocity in body frame + * @param x_pos [m] X position in local frame + * @param y_pos [m] Y position in local frame + * @param z_pos [m] Z position in local frame + * @param airspeed [m/s] Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate [rad/s] Angular rate in roll axis + * @param pitch_rate [rad/s] Angular rate in pitch axis + * @param yaw_rate [rad/s] Angular rate in yaw axis * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -165,23 +165,23 @@ static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param x_acc [m/s/s] X acceleration in body frame + * @param y_acc [m/s/s] Y acceleration in body frame + * @param z_acc [m/s/s] Z acceleration in body frame + * @param x_vel [m/s] X velocity in body frame + * @param y_vel [m/s] Y velocity in body frame + * @param z_vel [m/s] Z velocity in body frame + * @param x_pos [m] X position in local frame + * @param y_pos [m] Y position in local frame + * @param z_pos [m] Z position in local frame + * @param airspeed [m/s] Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate [rad/s] Angular rate in roll axis + * @param pitch_rate [rad/s] Angular rate in pitch axis + * @param yaw_rate [rad/s] Angular rate in yaw axis * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -265,23 +265,23 @@ static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t syst * @brief Send a control_system_state message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param x_acc [m/s/s] X acceleration in body frame + * @param y_acc [m/s/s] Y acceleration in body frame + * @param z_acc [m/s/s] Z acceleration in body frame + * @param x_vel [m/s] X velocity in body frame + * @param y_vel [m/s] Y velocity in body frame + * @param z_vel [m/s] Z velocity in body frame + * @param x_pos [m] X position in local frame + * @param y_pos [m] Y position in local frame + * @param z_pos [m] Z position in local frame + * @param airspeed [m/s] Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate [rad/s] Angular rate in roll axis + * @param pitch_rate [rad/s] Angular rate in pitch axis + * @param yaw_rate [rad/s] Angular rate in yaw axis */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -406,7 +406,7 @@ static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t * /** * @brief Get field time_usec from control_system_state message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg) { @@ -416,7 +416,7 @@ static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavl /** * @brief Get field x_acc from control_system_state message * - * @return X acceleration in body frame + * @return [m/s/s] X acceleration in body frame */ static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg) { @@ -426,7 +426,7 @@ static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_mes /** * @brief Get field y_acc from control_system_state message * - * @return Y acceleration in body frame + * @return [m/s/s] Y acceleration in body frame */ static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_mes /** * @brief Get field z_acc from control_system_state message * - * @return Z acceleration in body frame + * @return [m/s/s] Z acceleration in body frame */ static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_mes /** * @brief Get field x_vel from control_system_state message * - * @return X velocity in body frame + * @return [m/s] X velocity in body frame */ static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_mes /** * @brief Get field y_vel from control_system_state message * - * @return Y velocity in body frame + * @return [m/s] Y velocity in body frame */ static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_mes /** * @brief Get field z_vel from control_system_state message * - * @return Z velocity in body frame + * @return [m/s] Z velocity in body frame */ static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_mes /** * @brief Get field x_pos from control_system_state message * - * @return X position in local frame + * @return [m] X position in local frame */ static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg) { @@ -486,7 +486,7 @@ static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_mes /** * @brief Get field y_pos from control_system_state message * - * @return Y position in local frame + * @return [m] Y position in local frame */ static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg) { @@ -496,7 +496,7 @@ static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_mes /** * @brief Get field z_pos from control_system_state message * - * @return Z position in local frame + * @return [m] Z position in local frame */ static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg) { @@ -506,7 +506,7 @@ static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_mes /** * @brief Get field airspeed from control_system_state message * - * @return Airspeed, set to -1 if unknown + * @return [m/s] Airspeed, set to -1 if unknown */ static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg) { @@ -516,7 +516,7 @@ static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_ /** * @brief Get field vel_variance from control_system_state message * - * @return Variance of body velocity estimate + * @return Variance of body velocity estimate */ static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance) { @@ -526,7 +526,7 @@ static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const m /** * @brief Get field pos_variance from control_system_state message * - * @return Variance in local position + * @return Variance in local position */ static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance) { @@ -536,7 +536,7 @@ static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const m /** * @brief Get field q from control_system_state message * - * @return The attitude, represented as Quaternion + * @return The attitude, represented as Quaternion */ static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q) { @@ -546,7 +546,7 @@ static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_mess /** * @brief Get field roll_rate from control_system_state message * - * @return Angular rate in roll axis + * @return [rad/s] Angular rate in roll axis */ static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg) { @@ -556,7 +556,7 @@ static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink /** * @brief Get field pitch_rate from control_system_state message * - * @return Angular rate in pitch axis + * @return [rad/s] Angular rate in pitch axis */ static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg) { @@ -566,7 +566,7 @@ static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlin /** * @brief Get field yaw_rate from control_system_state message * - * @return Angular rate in yaw axis + * @return [rad/s] Angular rate in yaw axis */ static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_data_stream.h b/lib/main/MAVLink/common/mavlink_msg_data_stream.h index cceca20fae..36b688cbee 100755 --- a/lib/main/MAVLink/common/mavlink_msg_data_stream.h +++ b/lib/main/MAVLink/common/mavlink_msg_data_stream.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_DATA_STREAM 67 -MAVPACKED( + typedef struct __mavlink_data_stream_t { - uint16_t message_rate; /*< The message rate*/ - uint8_t stream_id; /*< The ID of the requested data stream*/ - uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ -}) mavlink_data_stream_t; + uint16_t message_rate; /*< [Hz] The message rate*/ + uint8_t stream_id; /*< The ID of the requested data stream*/ + uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ +} mavlink_data_stream_t; #define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 #define MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN 4 @@ -25,8 +25,8 @@ typedef struct __mavlink_data_stream_t { 67, \ "DATA_STREAM", \ 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ } \ } @@ -34,8 +34,8 @@ typedef struct __mavlink_data_stream_t { #define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ "DATA_STREAM", \ 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ } \ } @@ -47,9 +47,9 @@ typedef struct __mavlink_data_stream_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. + * @param stream_id The ID of the requested data stream + * @param message_rate [Hz] The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. + * @param stream_id The ID of the requested data stream + * @param message_rate [Hz] The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, ui * @brief Send a data_stream message * @param chan MAVLink channel to send the message * - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. + * @param stream_id The ID of the requested data stream + * @param message_rate [Hz] The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field stream_id from data_stream message * - * @return The ID of the requested data stream + * @return The ID of the requested data stream */ static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_messag /** * @brief Get field message_rate from data_stream message * - * @return The message rate + * @return [Hz] The message rate */ static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_me /** * @brief Get field on_off from data_stream message * - * @return 1 stream is enabled, 0 stream is stopped. + * @return 1 stream is enabled, 0 stream is stopped. */ static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_data_transmission_handshake.h b/lib/main/MAVLink/common/mavlink_msg_data_transmission_handshake.h index f607e39768..45fe60680a 100755 --- a/lib/main/MAVLink/common/mavlink_msg_data_transmission_handshake.h +++ b/lib/main/MAVLink/common/mavlink_msg_data_transmission_handshake.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 -MAVPACKED( + typedef struct __mavlink_data_transmission_handshake_t { - uint32_t size; /*< total data size in bytes (set on ACK only)*/ - uint16_t width; /*< Width of a matrix or image*/ - uint16_t height; /*< Height of a matrix or image*/ - uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/ - uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/ - uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/ - uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/ -}) mavlink_data_transmission_handshake_t; + uint32_t size; /*< [bytes] total data size (set on ACK only).*/ + uint16_t width; /*< Width of a matrix or image.*/ + uint16_t height; /*< Height of a matrix or image.*/ + uint16_t packets; /*< Number of packets being sent (set on ACK only).*/ + uint8_t type; /*< Type of requested/acknowledged data.*/ + uint8_t payload; /*< [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).*/ + uint8_t jpg_quality; /*< [%] JPEG quality. Values: [1-100].*/ +} mavlink_data_transmission_handshake_t; #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN 13 @@ -29,11 +29,11 @@ typedef struct __mavlink_data_transmission_handshake_t { 130, \ "DATA_TRANSMISSION_HANDSHAKE", \ 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ + { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ } \ @@ -42,11 +42,11 @@ typedef struct __mavlink_data_transmission_handshake_t { #define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ "DATA_TRANSMISSION_HANDSHAKE", \ 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ + { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ } \ @@ -59,13 +59,13 @@ typedef struct __mavlink_data_transmission_handshake_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] + * @param type Type of requested/acknowledged data. + * @param size [bytes] total data size (set on ACK only). + * @param width Width of a matrix or image. + * @param height Height of a matrix or image. + * @param packets Number of packets being sent (set on ACK only). + * @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). + * @param jpg_quality [%] JPEG quality. Values: [1-100]. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] + * @param type Type of requested/acknowledged data. + * @param size [bytes] total data size (set on ACK only). + * @param width Width of a matrix or image. + * @param height Height of a matrix or image. + * @param packets Number of packets being sent (set on ACK only). + * @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). + * @param jpg_quality [%] JPEG quality. Values: [1-100]. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8 * @brief Send a data_transmission_handshake message * @param chan MAVLink channel to send the message * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] + * @param type Type of requested/acknowledged data. + * @param size [bytes] total data size (set on ACK only). + * @param width Width of a matrix or image. + * @param height Height of a matrix or image. + * @param packets Number of packets being sent (set on ACK only). + * @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). + * @param jpg_quality [%] JPEG quality. Values: [1-100]. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_mess /** * @brief Get field type from data_transmission_handshake message * - * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @return Type of requested/acknowledged data. */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mav /** * @brief Get field size from data_transmission_handshake message * - * @return total data size in bytes (set on ACK only) + * @return [bytes] total data size (set on ACK only). */ static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const ma /** * @brief Get field width from data_transmission_handshake message * - * @return Width of a matrix or image + * @return Width of a matrix or image. */ static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const m /** * @brief Get field height from data_transmission_handshake message * - * @return Height of a matrix or image + * @return Height of a matrix or image. */ static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const /** * @brief Get field packets from data_transmission_handshake message * - * @return number of packets beeing sent (set on ACK only) + * @return Number of packets being sent (set on ACK only). */ static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const /** * @brief Get field payload from data_transmission_handshake message * - * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @return [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const /** * @brief Get field jpg_quality from data_transmission_handshake message * - * @return JPEG quality out of [1,100] + * @return [%] JPEG quality. Values: [1-100]. */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_debug.h b/lib/main/MAVLink/common/mavlink_msg_debug.h index d762a89dee..85814e366c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_debug.h +++ b/lib/main/MAVLink/common/mavlink_msg_debug.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_DEBUG 254 -MAVPACKED( + typedef struct __mavlink_debug_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float value; /*< DEBUG value*/ - uint8_t ind; /*< index of debug variable*/ -}) mavlink_debug_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float value; /*< DEBUG value*/ + uint8_t ind; /*< index of debug variable*/ +} mavlink_debug_t; #define MAVLINK_MSG_ID_DEBUG_LEN 9 #define MAVLINK_MSG_ID_DEBUG_MIN_LEN 9 @@ -26,8 +26,8 @@ typedef struct __mavlink_debug_t { "DEBUG", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ } \ } #else @@ -35,8 +35,8 @@ typedef struct __mavlink_debug_t { "DEBUG", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_debug_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param ind index of debug variable + * @param value DEBUG value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param ind index of debug variable + * @param value DEBUG value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t * @brief Send a debug message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param ind index of debug variable + * @param value DEBUG value */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink /** * @brief Get field time_boot_ms from debug message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_ /** * @brief Get field ind from debug message * - * @return index of debug variable + * @return index of debug variable */ static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) /** * @brief Get field value from debug message * - * @return DEBUG value + * @return DEBUG value */ static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_debug_vect.h b/lib/main/MAVLink/common/mavlink_msg_debug_vect.h index ac485af943..1cb8d77ab5 100755 --- a/lib/main/MAVLink/common/mavlink_msg_debug_vect.h +++ b/lib/main/MAVLink/common/mavlink_msg_debug_vect.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_DEBUG_VECT 250 -MAVPACKED( + typedef struct __mavlink_debug_vect_t { - uint64_t time_usec; /*< Timestamp*/ - float x; /*< x*/ - float y; /*< y*/ - float z; /*< z*/ - char name[10]; /*< Name*/ -}) mavlink_debug_vect_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float x; /*< x*/ + float y; /*< y*/ + float z; /*< z*/ + char name[10]; /*< Name*/ +} mavlink_debug_vect_t; #define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 #define MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN 30 @@ -27,22 +27,22 @@ typedef struct __mavlink_debug_vect_t { 250, \ "DEBUG_VECT", \ 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ + { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ + { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ "DEBUG_VECT", \ 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ + { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ + { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ } \ } #endif @@ -53,11 +53,11 @@ typedef struct __mavlink_debug_vect_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z + * @param name Name + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param x x + * @param y y + * @param z z * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z + * @param name Name + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param x x + * @param y y + * @param z z * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uin * @brief Send a debug_vect message * @param chan MAVLink channel to send the message * - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z + * @param name Name + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param x x + * @param y y + * @param z z */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field name from debug_vect message * - * @return Name + * @return Name */ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) { @@ -246,7 +246,7 @@ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* /** * @brief Get field time_usec from debug_vect message * - * @return Timestamp + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) { @@ -256,7 +256,7 @@ static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_messag /** * @brief Get field x from debug_vect message * - * @return x + * @return x */ static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) { @@ -266,7 +266,7 @@ static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) /** * @brief Get field y from debug_vect message * - * @return y + * @return y */ static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) /** * @brief Get field z from debug_vect message * - * @return z + * @return z */ static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_distance_sensor.h b/lib/main/MAVLink/common/mavlink_msg_distance_sensor.h index 2a52e69293..a5b0107be3 100755 --- a/lib/main/MAVLink/common/mavlink_msg_distance_sensor.h +++ b/lib/main/MAVLink/common/mavlink_msg_distance_sensor.h @@ -3,17 +3,17 @@ #define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 -MAVPACKED( + typedef struct __mavlink_distance_sensor_t { - uint32_t time_boot_ms; /*< Time since system boot*/ - uint16_t min_distance; /*< Minimum distance the sensor can measure in centimeters*/ - uint16_t max_distance; /*< Maximum distance the sensor can measure in centimeters*/ - uint16_t current_distance; /*< Current distance reading*/ - uint8_t type; /*< Type from MAV_DISTANCE_SENSOR enum.*/ - uint8_t id; /*< Onboard ID of the sensor*/ - uint8_t orientation; /*< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.*/ - uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/ -}) mavlink_distance_sensor_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure*/ + uint16_t max_distance; /*< [cm] Maximum distance the sensor can measure*/ + uint16_t current_distance; /*< [cm] Current distance reading*/ + uint8_t type; /*< Type of distance sensor.*/ + uint8_t id; /*< Onboard ID of the sensor*/ + uint8_t orientation; /*< Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270*/ + uint8_t covariance; /*< [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.*/ +} mavlink_distance_sensor_t; #define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 #define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14 @@ -62,14 +62,14 @@ typedef struct __mavlink_distance_sensor_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param min_distance [cm] Minimum distance the sensor can measure + * @param max_distance [cm] Maximum distance the sensor can measure + * @param current_distance [cm] Current distance reading + * @param type Type of distance sensor. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 + * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param min_distance [cm] Minimum distance the sensor can measure + * @param max_distance [cm] Maximum distance the sensor can measure + * @param current_distance [cm] Current distance reading + * @param type Type of distance sensor. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 + * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id * @brief Send a distance_sensor message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param min_distance [cm] Minimum distance the sensor can measure + * @param max_distance [cm] Maximum distance the sensor can measure + * @param current_distance [cm] Current distance reading + * @param type Type of distance sensor. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 + * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -286,7 +286,7 @@ static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbu /** * @brief Get field time_boot_ms from distance_sensor message * - * @return Time since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) { @@ -296,7 +296,7 @@ static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlin /** * @brief Get field min_distance from distance_sensor message * - * @return Minimum distance the sensor can measure in centimeters + * @return [cm] Minimum distance the sensor can measure */ static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) { @@ -306,7 +306,7 @@ static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlin /** * @brief Get field max_distance from distance_sensor message * - * @return Maximum distance the sensor can measure in centimeters + * @return [cm] Maximum distance the sensor can measure */ static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlin /** * @brief Get field current_distance from distance_sensor message * - * @return Current distance reading + * @return [cm] Current distance reading */ static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const ma /** * @brief Get field type from distance_sensor message * - * @return Type from MAV_DISTANCE_SENSOR enum. + * @return Type of distance sensor. */ static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message /** * @brief Get field id from distance_sensor message * - * @return Onboard ID of the sensor + * @return Onboard ID of the sensor */ static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t /** * @brief Get field orientation from distance_sensor message * - * @return Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @return Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 */ static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_ /** * @brief Get field covariance from distance_sensor message * - * @return Measurement covariance in centimeters, 0 for unknown / invalid readings + * @return [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown. */ static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_encapsulated_data.h b/lib/main/MAVLink/common/mavlink_msg_encapsulated_data.h index 5e9bc926ec..bfcf511b92 100755 --- a/lib/main/MAVLink/common/mavlink_msg_encapsulated_data.h +++ b/lib/main/MAVLink/common/mavlink_msg_encapsulated_data.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 -MAVPACKED( + typedef struct __mavlink_encapsulated_data_t { - uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ - uint8_t data[253]; /*< image data bytes*/ -}) mavlink_encapsulated_data_t; + uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ + uint8_t data[253]; /*< image data bytes*/ +} mavlink_encapsulated_data_t; #define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 #define MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN 255 @@ -44,8 +44,8 @@ typedef struct __mavlink_encapsulated_data_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -73,8 +73,8 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -128,8 +128,8 @@ static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_ * @brief Send a encapsulated_data message * @param chan MAVLink channel to send the message * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -194,7 +194,7 @@ static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msg /** * @brief Get field seqnr from encapsulated_data message * - * @return sequence number (starting with 0 on every transmission) + * @return sequence number (starting with 0 on every transmission) */ static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) { @@ -204,7 +204,7 @@ static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_mes /** * @brief Get field data from encapsulated_data message * - * @return image data bytes + * @return image data bytes */ static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) { diff --git a/lib/main/MAVLink/common/mavlink_msg_estimator_status.h b/lib/main/MAVLink/common/mavlink_msg_estimator_status.h index 2b7c6c09a3..bc5499b920 100755 --- a/lib/main/MAVLink/common/mavlink_msg_estimator_status.h +++ b/lib/main/MAVLink/common/mavlink_msg_estimator_status.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230 -MAVPACKED( + typedef struct __mavlink_estimator_status_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float vel_ratio; /*< Velocity innovation test ratio*/ - float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ - float pos_vert_ratio; /*< Vertical position innovation test ratio*/ - float mag_ratio; /*< Magnetometer innovation test ratio*/ - float hagl_ratio; /*< Height above terrain innovation test ratio*/ - float tas_ratio; /*< True airspeed innovation test ratio*/ - float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/ - float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/ - uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/ -}) mavlink_estimator_status_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float vel_ratio; /*< Velocity innovation test ratio*/ + float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ + float pos_vert_ratio; /*< Vertical position innovation test ratio*/ + float mag_ratio; /*< Magnetometer innovation test ratio*/ + float hagl_ratio; /*< Height above terrain innovation test ratio*/ + float tas_ratio; /*< True airspeed innovation test ratio*/ + float pos_horiz_accuracy; /*< [m] Horizontal position 1-STD accuracy relative to the EKF local origin*/ + float pos_vert_accuracy; /*< [m] Vertical position 1-STD accuracy relative to the EKF local origin*/ + uint16_t flags; /*< Bitmap indicating which EKF outputs are valid.*/ +} mavlink_estimator_status_t; #define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42 #define MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN 42 @@ -33,6 +33,7 @@ typedef struct __mavlink_estimator_status_t { "ESTIMATOR_STATUS", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ @@ -41,7 +42,6 @@ typedef struct __mavlink_estimator_status_t { { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ } \ } #else @@ -49,6 +49,7 @@ typedef struct __mavlink_estimator_status_t { "ESTIMATOR_STATUS", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ @@ -57,7 +58,6 @@ typedef struct __mavlink_estimator_status_t { { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ } \ } #endif @@ -68,16 +68,16 @@ typedef struct __mavlink_estimator_status_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param flags Bitmap indicating which EKF outputs are valid. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin + * @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param flags Bitmap indicating which EKF outputs are valid. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin + * @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_i * @brief Send a estimator_status message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param flags Bitmap indicating which EKF outputs are valid. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin + * @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgb /** * @brief Get field time_usec from estimator_status message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_ /** * @brief Get field flags from estimator_status message * - * @return Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @return Bitmap indicating which EKF outputs are valid. */ static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_mess /** * @brief Get field vel_ratio from estimator_status message * - * @return Velocity innovation test ratio + * @return Velocity innovation test ratio */ static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_mes /** * @brief Get field pos_horiz_ratio from estimator_status message * - * @return Horizontal position innovation test ratio + * @return Horizontal position innovation test ratio */ static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavli /** * @brief Get field pos_vert_ratio from estimator_status message * - * @return Vertical position innovation test ratio + * @return Vertical position innovation test ratio */ static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlin /** * @brief Get field mag_ratio from estimator_status message * - * @return Magnetometer innovation test ratio + * @return Magnetometer innovation test ratio */ static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_mes /** * @brief Get field hagl_ratio from estimator_status message * - * @return Height above terrain innovation test ratio + * @return Height above terrain innovation test ratio */ static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_me /** * @brief Get field tas_ratio from estimator_status message * - * @return True airspeed innovation test ratio + * @return True airspeed innovation test ratio */ static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_mes /** * @brief Get field pos_horiz_accuracy from estimator_status message * - * @return Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @return [m] Horizontal position 1-STD accuracy relative to the EKF local origin */ static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const ma /** * @brief Get field pos_vert_accuracy from estimator_status message * - * @return Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @return [m] Vertical position 1-STD accuracy relative to the EKF local origin */ static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_extended_sys_state.h b/lib/main/MAVLink/common/mavlink_msg_extended_sys_state.h index 329a774afb..2eeeed0c0b 100755 --- a/lib/main/MAVLink/common/mavlink_msg_extended_sys_state.h +++ b/lib/main/MAVLink/common/mavlink_msg_extended_sys_state.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245 -MAVPACKED( + typedef struct __mavlink_extended_sys_state_t { - uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ -}) mavlink_extended_sys_state_t; + uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ + uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ +} mavlink_extended_sys_state_t; #define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2 #define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN 2 @@ -44,8 +44,8 @@ typedef struct __mavlink_extended_sys_state_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, ui * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system * @brief Send a extended_sys_state message * @param chan MAVLink channel to send the message * - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_extended_sys_state_send_buf(mavlink_message_t *ms /** * @brief Get field vtol_state from extended_sys_state message * - * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. */ static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlin /** * @brief Get field landed_state from extended_sys_state message * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. */ static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_fence_status.h b/lib/main/MAVLink/common/mavlink_msg_fence_status.h new file mode 100644 index 0000000000..d15f768d9b --- /dev/null +++ b/lib/main/MAVLink/common/mavlink_msg_fence_status.h @@ -0,0 +1,288 @@ +#pragma once +// MESSAGE FENCE_STATUS PACKING + +#define MAVLINK_MSG_ID_FENCE_STATUS 162 + + +typedef struct __mavlink_fence_status_t { + uint32_t breach_time; /*< [ms] Time (since boot) of last breach.*/ + uint16_t breach_count; /*< Number of fence breaches.*/ + uint8_t breach_status; /*< Breach status (0 if currently inside fence, 1 if outside).*/ + uint8_t breach_type; /*< Last breach type.*/ +} mavlink_fence_status_t; + +#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8 +#define MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN 8 +#define MAVLINK_MSG_ID_162_LEN 8 +#define MAVLINK_MSG_ID_162_MIN_LEN 8 + +#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189 +#define MAVLINK_MSG_ID_162_CRC 189 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ + 162, \ + "FENCE_STATUS", \ + 4, \ + { { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \ + { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \ + { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \ + { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ + "FENCE_STATUS", \ + 4, \ + { { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \ + { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \ + { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \ + { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \ + } \ +} +#endif + +/** + * @brief Pack a fence_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param breach_status Breach status (0 if currently inside fence, 1 if outside). + * @param breach_count Number of fence breaches. + * @param breach_type Last breach type. + * @param breach_time [ms] Time (since boot) of last breach. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#else + mavlink_fence_status_t packet; + packet.breach_time = breach_time; + packet.breach_count = breach_count; + packet.breach_status = breach_status; + packet.breach_type = breach_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +} + +/** + * @brief Pack a fence_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param breach_status Breach status (0 if currently inside fence, 1 if outside). + * @param breach_count Number of fence breaches. + * @param breach_type Last breach type. + * @param breach_time [ms] Time (since boot) of last breach. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#else + mavlink_fence_status_t packet; + packet.breach_time = breach_time; + packet.breach_count = breach_count; + packet.breach_status = breach_status; + packet.breach_type = breach_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +} + +/** + * @brief Encode a fence_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param fence_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) +{ + return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time); +} + +/** + * @brief Encode a fence_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param fence_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) +{ + return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time); +} + +/** + * @brief Send a fence_status message + * @param chan MAVLink channel to send the message + * + * @param breach_status Breach status (0 if currently inside fence, 1 if outside). + * @param breach_count Number of fence breaches. + * @param breach_type Last breach type. + * @param breach_time [ms] Time (since boot) of last breach. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#else + mavlink_fence_status_t packet; + packet.breach_time = breach_time; + packet.breach_count = breach_count; + packet.breach_status = breach_status; + packet.breach_type = breach_type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#endif +} + +/** + * @brief Send a fence_status message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan, const mavlink_fence_status_t* fence_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)fence_status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#endif +} + +#if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#else + mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf; + packet->breach_time = breach_time; + packet->breach_count = breach_count; + packet->breach_status = breach_status; + packet->breach_type = breach_type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#endif +} +#endif + +#endif + +// MESSAGE FENCE_STATUS UNPACKING + + +/** + * @brief Get field breach_status from fence_status message + * + * @return Breach status (0 if currently inside fence, 1 if outside). + */ +static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field breach_count from fence_status message + * + * @return Number of fence breaches. + */ +static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field breach_type from fence_status message + * + * @return Last breach type. + */ +static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field breach_time from fence_status message + * + * @return [ms] Time (since boot) of last breach. + */ +static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a fence_status message into a struct + * + * @param msg The message to decode + * @param fence_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg); + fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg); + fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg); + fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FENCE_STATUS_LEN; + memset(fence_status, 0, MAVLINK_MSG_ID_FENCE_STATUS_LEN); + memcpy(fence_status, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h b/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h index 07b5a3ef64..0dd4d0530d 100755 --- a/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h +++ b/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110 -MAVPACKED( + typedef struct __mavlink_file_transfer_protocol_t { - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ -}) mavlink_file_transfer_protocol_t; + uint8_t target_network; /*< Network ID (0 for broadcast)*/ + uint8_t target_system; /*< System ID (0 for broadcast)*/ + uint8_t target_component; /*< Component ID (0 for broadcast)*/ + uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ +} mavlink_file_transfer_protocol_t; #define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254 #define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN 254 @@ -50,10 +50,10 @@ typedef struct __mavlink_file_transfer_protocol_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t sy * @brief Send a file_transfer_protocol message * @param chan MAVLink channel to send the message * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t /** * @brief Get field target_network from file_transfer_protocol message * - * @return Network ID (0 for broadcast) + * @return Network ID (0 for broadcast) */ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(cons /** * @brief Get field target_system from file_transfer_protocol message * - * @return System ID (0 for broadcast) + * @return System ID (0 for broadcast) */ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg) { @@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const /** * @brief Get field target_component from file_transfer_protocol message * - * @return Component ID (0 for broadcast) + * @return Component ID (0 for broadcast) */ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg) { @@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(co /** * @brief Get field payload from file_transfer_protocol message * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. */ static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload) { diff --git a/lib/main/MAVLink/common/mavlink_msg_follow_target.h b/lib/main/MAVLink/common/mavlink_msg_follow_target.h index bfd45f649e..01d03ab510 100755 --- a/lib/main/MAVLink/common/mavlink_msg_follow_target.h +++ b/lib/main/MAVLink/common/mavlink_msg_follow_target.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_FOLLOW_TARGET 144 -MAVPACKED( + typedef struct __mavlink_follow_target_t { - uint64_t timestamp; /*< Timestamp in milliseconds since system boot*/ - uint64_t custom_state; /*< button states or switches of a tracker device*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - float alt; /*< AMSL, in meters*/ - float vel[3]; /*< target velocity (0,0,0) for unknown*/ - float acc[3]; /*< linear target acceleration (0,0,0) for unknown*/ - float attitude_q[4]; /*< (1 0 0 0 for unknown)*/ - float rates[3]; /*< (0 0 0 for unknown)*/ - float position_cov[3]; /*< eph epv*/ - uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ -}) mavlink_follow_target_t; + uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/ + uint64_t custom_state; /*< button states or switches of a tracker device*/ + int32_t lat; /*< [degE7] Latitude (WGS84)*/ + int32_t lon; /*< [degE7] Longitude (WGS84)*/ + float alt; /*< [m] Altitude (MSL)*/ + float vel[3]; /*< [m/s] target velocity (0,0,0) for unknown*/ + float acc[3]; /*< [m/s/s] linear target acceleration (0,0,0) for unknown*/ + float attitude_q[4]; /*< (1 0 0 0 for unknown)*/ + float rates[3]; /*< (0 0 0 for unknown)*/ + float position_cov[3]; /*< eph epv*/ + uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ +} mavlink_follow_target_t; #define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 #define MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN 93 @@ -38,7 +38,7 @@ typedef struct __mavlink_follow_target_t { "FOLLOW_TARGET", \ 11, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ + { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ @@ -47,7 +47,7 @@ typedef struct __mavlink_follow_target_t { { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ + { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ } \ } #else @@ -55,7 +55,7 @@ typedef struct __mavlink_follow_target_t { "FOLLOW_TARGET", \ 11, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ + { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ @@ -64,7 +64,7 @@ typedef struct __mavlink_follow_target_t { { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ + { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ } \ } #endif @@ -75,17 +75,17 @@ typedef struct __mavlink_follow_target_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device + * @param timestamp [ms] Timestamp (time since system boot). + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [m] Altitude (MSL) + * @param vel [m/s] target velocity (0,0,0) for unknown + * @param acc [m/s/s] linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -131,17 +131,17 @@ static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device + * @param timestamp [ms] Timestamp (time since system boot). + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [m] Altitude (MSL) + * @param vel [m/s] target velocity (0,0,0) for unknown + * @param acc [m/s/s] linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -213,17 +213,17 @@ static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, * @brief Send a follow_target message * @param chan MAVLink channel to send the message * - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device + * @param timestamp [ms] Timestamp (time since system boot). + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [m] Altitude (MSL) + * @param vel [m/s] target velocity (0,0,0) for unknown + * @param acc [m/s/s] linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -324,7 +324,7 @@ static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field timestamp from follow_target message * - * @return Timestamp in milliseconds since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_mes /** * @brief Get field est_capabilities from follow_target message * - * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) */ static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavli /** * @brief Get field lat from follow_target message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* /** * @brief Get field lon from follow_target message * - * @return Longitude (WGS84), in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* /** * @brief Get field alt from follow_target message * - * @return AMSL, in meters + * @return [m] Altitude (MSL) */ static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* m /** * @brief Get field vel from follow_target message * - * @return target velocity (0,0,0) for unknown + * @return [m/s] target velocity (0,0,0) for unknown */ static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel) { @@ -384,7 +384,7 @@ static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t /** * @brief Get field acc from follow_target message * - * @return linear target acceleration (0,0,0) for unknown + * @return [m/s/s] linear target acceleration (0,0,0) for unknown */ static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc) { @@ -394,7 +394,7 @@ static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t /** * @brief Get field attitude_q from follow_target message * - * @return (1 0 0 0 for unknown) + * @return (1 0 0 0 for unknown) */ static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t* msg, float *attitude_q) { @@ -404,7 +404,7 @@ static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_me /** * @brief Get field rates from follow_target message * - * @return (0 0 0 for unknown) + * @return (0 0 0 for unknown) */ static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t* msg, float *rates) { @@ -414,7 +414,7 @@ static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message /** * @brief Get field position_cov from follow_target message * - * @return eph epv + * @return eph epv */ static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t* msg, float *position_cov) { @@ -424,7 +424,7 @@ static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_ /** * @brief Get field custom_state from follow_target message * - * @return button states or switches of a tracker device + * @return button states or switches of a tracker device */ static inline uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_global_position_int.h b/lib/main/MAVLink/common/mavlink_msg_global_position_int.h index ef6267d2e1..8b601f2347 100755 --- a/lib/main/MAVLink/common/mavlink_msg_global_position_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_global_position_int.h @@ -3,18 +3,18 @@ #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 -MAVPACKED( + typedef struct __mavlink_global_position_int_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/ - uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ -}) mavlink_global_position_int_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + int32_t lat; /*< [degE7] Latitude, expressed*/ + int32_t lon; /*< [degE7] Longitude, expressed*/ + int32_t alt; /*< [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.*/ + int32_t relative_alt; /*< [mm] Altitude above ground*/ + int16_t vx; /*< [cm/s] Ground X Speed (Latitude, positive north)*/ + int16_t vy; /*< [cm/s] Ground Y Speed (Longitude, positive east)*/ + int16_t vz; /*< [cm/s] Ground Z Speed (Altitude, positive down)*/ + uint16_t hdg; /*< [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ +} mavlink_global_position_int_t; #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28 @@ -65,15 +65,15 @@ typedef struct __mavlink_global_position_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param lat [degE7] Latitude, expressed + * @param lon [degE7] Longitude, expressed + * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. + * @param relative_alt [mm] Altitude above ground + * @param vx [cm/s] Ground X Speed (Latitude, positive north) + * @param vy [cm/s] Ground Y Speed (Longitude, positive east) + * @param vz [cm/s] Ground Z Speed (Altitude, positive down) + * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -117,15 +117,15 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param lat [degE7] Latitude, expressed + * @param lon [degE7] Longitude, expressed + * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. + * @param relative_alt [mm] Altitude above ground + * @param vx [cm/s] Ground X Speed (Latitude, positive north) + * @param vy [cm/s] Ground Y Speed (Longitude, positive east) + * @param vz [cm/s] Ground Z Speed (Altitude, positive down) + * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -195,15 +195,15 @@ static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t syste * @brief Send a global_position_int message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param lat [degE7] Latitude, expressed + * @param lon [degE7] Longitude, expressed + * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. + * @param relative_alt [mm] Altitude above ground + * @param vx [cm/s] Ground X Speed (Latitude, positive north) + * @param vy [cm/s] Ground Y Speed (Longitude, positive east) + * @param vz [cm/s] Ground Z Speed (Altitude, positive down) + * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -300,7 +300,7 @@ static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *m /** * @brief Get field time_boot_ms from global_position_int message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) { @@ -310,7 +310,7 @@ static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const ma /** * @brief Get field lat from global_position_int message * - * @return Latitude, expressed as degrees * 1E7 + * @return [degE7] Latitude, expressed */ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) { @@ -320,7 +320,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_mess /** * @brief Get field lon from global_position_int message * - * @return Longitude, expressed as degrees * 1E7 + * @return [degE7] Longitude, expressed */ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) { @@ -330,7 +330,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess /** * @brief Get field alt from global_position_int message * - * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @return [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. */ static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) { @@ -340,7 +340,7 @@ static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_mess /** * @brief Get field relative_alt from global_position_int message * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + * @return [mm] Altitude above ground */ static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) { @@ -350,7 +350,7 @@ static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mav /** * @brief Get field vx from global_position_int message * - * @return Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @return [cm/s] Ground X Speed (Latitude, positive north) */ static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) { @@ -360,7 +360,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_messa /** * @brief Get field vy from global_position_int message * - * @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @return [cm/s] Ground Y Speed (Longitude, positive east) */ static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) { @@ -370,7 +370,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_messa /** * @brief Get field vz from global_position_int message * - * @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @return [cm/s] Ground Z Speed (Altitude, positive down) */ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa /** * @brief Get field hdg from global_position_int message * - * @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_global_position_int_cov.h b/lib/main/MAVLink/common/mavlink_msg_global_position_int_cov.h index 0d33faf58b..3cb44be787 100755 --- a/lib/main/MAVLink/common/mavlink_msg_global_position_int_cov.h +++ b/lib/main/MAVLink/common/mavlink_msg_global_position_int_cov.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 -MAVPACKED( + typedef struct __mavlink_global_position_int_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ - float vx; /*< Ground X Speed (Latitude), expressed as m/s*/ - float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/ - float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/ - float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -}) mavlink_global_position_int_cov_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + int32_t lat; /*< [degE7] Latitude*/ + int32_t lon; /*< [degE7] Longitude*/ + int32_t alt; /*< [mm] Altitude in meters above MSL*/ + int32_t relative_alt; /*< [mm] Altitude above ground*/ + float vx; /*< [m/s] Ground X Speed (Latitude)*/ + float vy; /*< [m/s] Ground Y Speed (Longitude)*/ + float vz; /*< [m/s] Ground Z Speed (Altitude)*/ + float covariance[36]; /*< Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/ + uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ +} mavlink_global_position_int_cov_t; #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 181 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 181 @@ -33,6 +33,7 @@ typedef struct __mavlink_global_position_int_cov_t { "GLOBAL_POSITION_INT_COV", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ @@ -41,7 +42,6 @@ typedef struct __mavlink_global_position_int_cov_t { { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ } \ } #else @@ -49,6 +49,7 @@ typedef struct __mavlink_global_position_int_cov_t { "GLOBAL_POSITION_INT_COV", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ @@ -57,7 +58,6 @@ typedef struct __mavlink_global_position_int_cov_t { { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ } \ } #endif @@ -68,16 +68,16 @@ typedef struct __mavlink_global_position_int_cov_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude in meters above MSL + * @param relative_alt [mm] Altitude above ground + * @param vx [m/s] Ground X Speed (Latitude) + * @param vy [m/s] Ground Y Speed (Longitude) + * @param vz [m/s] Ground Z Speed (Altitude) + * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -121,16 +121,16 @@ static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_i * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude in meters above MSL + * @param relative_alt [mm] Altitude above ground + * @param vx [m/s] Ground X Speed (Latitude) + * @param vy [m/s] Ground Y Speed (Longitude) + * @param vz [m/s] Ground Z Speed (Altitude) + * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -200,16 +200,16 @@ static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t s * @brief Send a global_position_int_cov message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude in meters above MSL + * @param relative_alt [mm] Altitude above ground + * @param vx [m/s] Ground X Speed (Latitude) + * @param vy [m/s] Ground Y Speed (Longitude) + * @param vz [m/s] Ground Z Speed (Altitude) + * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -306,7 +306,7 @@ static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_ /** * @brief Get field time_usec from global_position_int_cov message * - * @return Timestamp (microseconds since system boot or since UNIX epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const m /** * @brief Get field estimator_type from global_position_int_cov message * - * @return Class id of the estimator this estimate originated from. + * @return Class id of the estimator this estimate originated from. */ static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(con /** * @brief Get field lat from global_position_int_cov message * - * @return Latitude, expressed as degrees * 1E7 + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_ /** * @brief Get field lon from global_position_int_cov message * - * @return Longitude, expressed as degrees * 1E7 + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_ /** * @brief Get field alt from global_position_int_cov message * - * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @return [mm] Altitude in meters above MSL */ static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_ /** * @brief Get field relative_alt from global_position_int_cov message * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + * @return [mm] Altitude above ground */ static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const /** * @brief Get field vx from global_position_int_cov message * - * @return Ground X Speed (Latitude), expressed as m/s + * @return [m/s] Ground X Speed (Latitude) */ static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg) { @@ -376,7 +376,7 @@ static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_mes /** * @brief Get field vy from global_position_int_cov message * - * @return Ground Y Speed (Longitude), expressed as m/s + * @return [m/s] Ground Y Speed (Longitude) */ static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_mes /** * @brief Get field vz from global_position_int_cov message * - * @return Ground Z Speed (Altitude), expressed as m/s + * @return [m/s] Ground Z Speed (Altitude) */ static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_mes /** * @brief Get field covariance from global_position_int_cov message * - * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @return Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. */ static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance) { diff --git a/lib/main/MAVLink/common/mavlink_msg_global_vision_position_estimate.h b/lib/main/MAVLink/common/mavlink_msg_global_vision_position_estimate.h index 6b65eb0631..5f191fe3ad 100755 --- a/lib/main/MAVLink/common/mavlink_msg_global_vision_position_estimate.h +++ b/lib/main/MAVLink/common/mavlink_msg_global_vision_position_estimate.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 -MAVPACKED( + typedef struct __mavlink_global_vision_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_global_vision_position_estimate_t; + uint64_t usec; /*< [us] Timestamp (UNIX time or since system boot)*/ + float x; /*< [m] Global X position*/ + float y; /*< [m] Global Y position*/ + float z; /*< [m] Global Z position*/ + float roll; /*< [rad] Roll angle*/ + float pitch; /*< [rad] Pitch angle*/ + float yaw; /*< [rad] Yaw angle*/ +} mavlink_global_vision_position_estimate_t; #define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 #define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN 32 @@ -59,13 +59,13 @@ typedef struct __mavlink_global_vision_position_estimate_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or since system boot) + * @param x [m] Global X position + * @param y [m] Global Y position + * @param z [m] Global Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or since system boot) + * @param x [m] Global X position + * @param y [m] Global Y position + * @param z [m] Global Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(u * @brief Send a global_vision_position_estimate message * @param chan MAVLink channel to send the message * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or since system boot) + * @param x [m] Global X position + * @param y [m] Global Y position + * @param z [m] Global Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_ /** * @brief Get field usec from global_vision_position_estimate message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX time or since system boot) */ static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(cons /** * @brief Get field x from global_vision_position_estimate message * - * @return Global X position + * @return [m] Global X position */ static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavl /** * @brief Get field y from global_vision_position_estimate message * - * @return Global Y position + * @return [m] Global Y position */ static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavl /** * @brief Get field z from global_vision_position_estimate message * - * @return Global Z position + * @return [m] Global Z position */ static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavl /** * @brief Get field roll from global_vision_position_estimate message * - * @return Roll angle in rad + * @return [rad] Roll angle */ static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_roll(const m /** * @brief Get field pitch from global_vision_position_estimate message * - * @return Pitch angle in rad + * @return [rad] Pitch angle */ static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const /** * @brief Get field yaw from global_vision_position_estimate message * - * @return Yaw angle in rad + * @return [rad] Yaw angle */ static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps2_raw.h b/lib/main/MAVLink/common/mavlink_msg_gps2_raw.h index aeccc4eb33..330b7e96dd 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps2_raw.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps2_raw.h @@ -3,21 +3,21 @@ #define MAVLINK_MSG_ID_GPS2_RAW 124 -MAVPACKED( + typedef struct __mavlink_gps2_raw_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ - uint32_t dgps_age; /*< Age of DGPS info*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ - uint8_t dgps_numch; /*< Number of DGPS satellites*/ -}) mavlink_gps2_raw_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + int32_t lat; /*< [degE7] Latitude (WGS84)*/ + int32_t lon; /*< [degE7] Longitude (WGS84)*/ + int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/ + uint32_t dgps_age; /*< [ms] Age of DGPS info*/ + uint16_t eph; /*< [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX*/ + uint16_t epv; /*< [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX*/ + uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/ + uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ + uint8_t fix_type; /*< GPS fix type.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ + uint8_t dgps_numch; /*< Number of DGPS satellites*/ +} mavlink_gps2_raw_t; #define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 #define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35 @@ -35,17 +35,17 @@ typedef struct __mavlink_gps2_raw_t { "GPS2_RAW", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ + { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ } \ } #else @@ -53,17 +53,17 @@ typedef struct __mavlink_gps2_raw_t { "GPS2_RAW", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ + { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ } \ } #endif @@ -74,18 +74,18 @@ typedef struct __mavlink_gps2_raw_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type GPS fix type. + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [mm] Altitude (MSL). Positive for up. + * @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX + * @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX + * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age [ms] Age of DGPS info * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -135,18 +135,18 @@ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type GPS fix type. + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [mm] Altitude (MSL). Positive for up. + * @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX + * @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX + * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age [ms] Age of DGPS info * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -222,18 +222,18 @@ static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8 * @brief Send a gps2_raw message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type GPS fix type. + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [mm] Altitude (MSL). Positive for up. + * @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX + * @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX + * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age [ms] Age of DGPS info */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -342,7 +342,7 @@ static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field time_usec from gps2_raw message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_ /** * @brief Get field fix_type from gps2_raw message * - * @return See the GPS_FIX_TYPE enum. + * @return GPS fix type. */ static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* /** * @brief Get field lat from gps2_raw message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) /** * @brief Get field lon from gps2_raw message * - * @return Longitude (WGS84), in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) { @@ -382,7 +382,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) /** * @brief Get field alt from gps2_raw message * - * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @return [mm] Altitude (MSL). Positive for up. */ static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) { @@ -392,7 +392,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) /** * @brief Get field eph from gps2_raw message * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @return [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) { @@ -402,7 +402,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg /** * @brief Get field epv from gps2_raw message * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @return [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) { @@ -412,7 +412,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg /** * @brief Get field vel from gps2_raw message * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) { @@ -422,7 +422,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg /** * @brief Get field cog from gps2_raw message * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) { @@ -432,7 +432,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg /** * @brief Get field satellites_visible from gps2_raw message * - * @return Number of satellites visible. If unknown, set to 255 + * @return Number of satellites visible. If unknown, set to 255 */ static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) { @@ -442,7 +442,7 @@ static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_ /** * @brief Get field dgps_numch from gps2_raw message * - * @return Number of DGPS satellites + * @return Number of DGPS satellites */ static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) { @@ -452,7 +452,7 @@ static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_ /** * @brief Get field dgps_age from gps2_raw message * - * @return Age of DGPS info + * @return [ms] Age of DGPS info */ static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps2_rtk.h b/lib/main/MAVLink/common/mavlink_msg_gps2_rtk.h index e383647232..2af9b53ca7 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps2_rtk.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps2_rtk.h @@ -3,22 +3,22 @@ #define MAVLINK_MSG_ID_GPS2_RTK 128 -MAVPACKED( + typedef struct __mavlink_gps2_rtk_t { - uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ - uint32_t tow; /*< GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ - int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ - int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ -}) mavlink_gps2_rtk_t; + uint32_t time_last_baseline_ms; /*< [ms] Time since boot of last baseline message received.*/ + uint32_t tow; /*< [ms] GPS Time of Week of last baseline*/ + int32_t baseline_a_mm; /*< [mm] Current baseline in ECEF x or NED north component.*/ + int32_t baseline_b_mm; /*< [mm] Current baseline in ECEF y or NED east component.*/ + int32_t baseline_c_mm; /*< [mm] Current baseline in ECEF z or NED down component.*/ + uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ + int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ + uint16_t wn; /*< GPS Week Number of last baseline*/ + uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ + uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ + uint8_t rtk_rate; /*< [Hz] Rate of baseline messages being received by GPS*/ + uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ + uint8_t baseline_coords_type; /*< Coordinate system of baseline*/ +} mavlink_gps2_rtk_t; #define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 #define MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN 35 @@ -36,18 +36,18 @@ typedef struct __mavlink_gps2_rtk_t { "GPS2_RTK", \ 13, \ { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ } \ } #else @@ -55,18 +55,18 @@ typedef struct __mavlink_gps2_rtk_t { "GPS2_RTK", \ 13, \ { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ } \ } #endif @@ -77,19 +77,19 @@ typedef struct __mavlink_gps2_rtk_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow [ms] GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate [Hz] Rate of baseline messages being received by GPS + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline + * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. + * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. + * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -141,19 +141,19 @@ static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow [ms] GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate [Hz] Rate of baseline messages being received by GPS + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline + * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. + * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. + * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -231,19 +231,19 @@ static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8 * @brief Send a gps2_rtk message * @param chan MAVLink channel to send the message * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow [ms] GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate [Hz] Rate of baseline messages being received by GPS + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline + * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. + * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. + * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -356,7 +356,7 @@ static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field time_last_baseline_ms from gps2_rtk message * - * @return Time since boot of last baseline message received in ms. + * @return [ms] Time since boot of last baseline message received. */ static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavl /** * @brief Get field rtk_receiver_id from gps2_rtk message * - * @return Identification of connected RTK receiver. + * @return Identification of connected RTK receiver. */ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) { @@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_mes /** * @brief Get field wn from gps2_rtk message * - * @return GPS Week Number of last baseline + * @return GPS Week Number of last baseline */ static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) /** * @brief Get field tow from gps2_rtk message * - * @return GPS Time of Week of last baseline + * @return [ms] GPS Time of Week of last baseline */ static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg /** * @brief Get field rtk_health from gps2_rtk message * - * @return GPS-specific health report for RTK data. + * @return GPS-specific health report for RTK data. */ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) { @@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_ /** * @brief Get field rtk_rate from gps2_rtk message * - * @return Rate of baseline messages being received by GPS, in HZ + * @return [Hz] Rate of baseline messages being received by GPS */ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) { @@ -416,7 +416,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* /** * @brief Get field nsats from gps2_rtk message * - * @return Current number of sats used for RTK calculation. + * @return Current number of sats used for RTK calculation. */ static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) { @@ -426,7 +426,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* ms /** * @brief Get field baseline_coords_type from gps2_rtk message * - * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + * @return Coordinate system of baseline */ static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlin /** * @brief Get field baseline_a_mm from gps2_rtk message * - * @return Current baseline in ECEF x or NED north component in mm. + * @return [mm] Current baseline in ECEF x or NED north component. */ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_messa /** * @brief Get field baseline_b_mm from gps2_rtk message * - * @return Current baseline in ECEF y or NED east component in mm. + * @return [mm] Current baseline in ECEF y or NED east component. */ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_messa /** * @brief Get field baseline_c_mm from gps2_rtk message * - * @return Current baseline in ECEF z or NED down component in mm. + * @return [mm] Current baseline in ECEF z or NED down component. */ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_messa /** * @brief Get field accuracy from gps2_rtk message * - * @return Current estimate of baseline accuracy. + * @return Current estimate of baseline accuracy. */ static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t /** * @brief Get field iar_num_hypotheses from gps2_rtk message * - * @return Current number of integer ambiguity hypotheses. + * @return Current number of integer ambiguity hypotheses. */ static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_global_origin.h b/lib/main/MAVLink/common/mavlink_msg_gps_global_origin.h index 3008058f10..7719543ee2 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_global_origin.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_global_origin.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 -MAVPACKED( + typedef struct __mavlink_gps_global_origin_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ -}) mavlink_gps_global_origin_t; + int32_t latitude; /*< [degE7] Latitude (WGS84)*/ + int32_t longitude; /*< [degE7] Longitude (WGS84)*/ + int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ +} mavlink_gps_global_origin_t; #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN 12 @@ -47,9 +47,9 @@ typedef struct __mavlink_gps_global_origin_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_ * @brief Send a gps_global_origin message * @param chan MAVLink channel to send the message * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msg /** * @brief Get field latitude from gps_global_origin message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_m /** * @brief Get field longitude from gps_global_origin message * - * @return Longitude (WGS84), in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_ /** * @brief Get field altitude from gps_global_origin message * - * @return Altitude (AMSL), in meters * 1000 (positive for up) + * @return [mm] Altitude (MSL). Positive for up. */ static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_inject_data.h b/lib/main/MAVLink/common/mavlink_msg_gps_inject_data.h index 4fbd5fc976..ff6dc0ee91 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_inject_data.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_inject_data.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 -MAVPACKED( + typedef struct __mavlink_gps_inject_data_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t len; /*< data length*/ - uint8_t data[110]; /*< raw data (110 is enough for 12 satellites of RTCMv2)*/ -}) mavlink_gps_inject_data_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t len; /*< [bytes] Data length*/ + uint8_t data[110]; /*< Raw data (110 is enough for 12 satellites of RTCMv2)*/ +} mavlink_gps_inject_data_t; #define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 #define MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN 113 @@ -50,10 +50,10 @@ typedef struct __mavlink_gps_inject_data_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @param target_system System ID + * @param target_component Component ID + * @param len [bytes] Data length + * @param data Raw data (110 is enough for 12 satellites of RTCMv2) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @param target_system System ID + * @param target_component Component ID + * @param len [bytes] Data length + * @param data Raw data (110 is enough for 12 satellites of RTCMv2) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id * @brief Send a gps_inject_data message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @param target_system System ID + * @param target_component Component ID + * @param len [bytes] Data length + * @param data Raw data (110 is enough for 12 satellites of RTCMv2) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbu /** * @brief Get field target_system from gps_inject_data message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlin /** * @brief Get field target_component from gps_inject_data message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) { @@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mav /** * @brief Get field len from gps_inject_data message * - * @return data length + * @return [bytes] Data length */ static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) { @@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_ /** * @brief Get field data from gps_inject_data message * - * @return raw data (110 is enough for 12 satellites of RTCMv2) + * @return Raw data (110 is enough for 12 satellites of RTCMv2) */ static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_input.h b/lib/main/MAVLink/common/mavlink_msg_gps_input.h index 5fb9e9c5a5..6268b11af3 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_input.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_input.h @@ -3,27 +3,27 @@ #define MAVLINK_MSG_ID_GPS_INPUT 232 -MAVPACKED( + typedef struct __mavlink_gps_input_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - uint32_t time_week_ms; /*< GPS time (milliseconds from start of GPS week)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - float alt; /*< Altitude (AMSL, not WGS84), in m (positive for up)*/ - float hdop; /*< GPS HDOP horizontal dilution of position in m*/ - float vdop; /*< GPS VDOP vertical dilution of position in m*/ - float vn; /*< GPS velocity in m/s in NORTH direction in earth-fixed NED frame*/ - float ve; /*< GPS velocity in m/s in EAST direction in earth-fixed NED frame*/ - float vd; /*< GPS velocity in m/s in DOWN direction in earth-fixed NED frame*/ - float speed_accuracy; /*< GPS speed accuracy in m/s*/ - float horiz_accuracy; /*< GPS horizontal accuracy in m*/ - float vert_accuracy; /*< GPS vertical accuracy in m*/ - uint16_t ignore_flags; /*< Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.*/ - uint16_t time_week; /*< GPS week number*/ - uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/ - uint8_t satellites_visible; /*< Number of satellites visible.*/ -}) mavlink_gps_input_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint32_t time_week_ms; /*< [ms] GPS time (from start of GPS week)*/ + int32_t lat; /*< [degE7] Latitude (WGS84)*/ + int32_t lon; /*< [degE7] Longitude (WGS84)*/ + float alt; /*< [m] Altitude (MSL). Positive for up.*/ + float hdop; /*< [m] GPS HDOP horizontal dilution of position*/ + float vdop; /*< [m] GPS VDOP vertical dilution of position*/ + float vn; /*< [m/s] GPS velocity in north direction in earth-fixed NED frame*/ + float ve; /*< [m/s] GPS velocity in east direction in earth-fixed NED frame*/ + float vd; /*< [m/s] GPS velocity in down direction in earth-fixed NED frame*/ + float speed_accuracy; /*< [m/s] GPS speed accuracy*/ + float horiz_accuracy; /*< [m] GPS horizontal accuracy*/ + float vert_accuracy; /*< [m] GPS vertical accuracy*/ + uint16_t ignore_flags; /*< Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.*/ + uint16_t time_week; /*< GPS week number*/ + uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/ + uint8_t satellites_visible; /*< Number of satellites visible.*/ +} mavlink_gps_input_t; #define MAVLINK_MSG_ID_GPS_INPUT_LEN 63 #define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63 @@ -41,7 +41,11 @@ typedef struct __mavlink_gps_input_t { "GPS_INPUT", \ 18, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ + { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ + { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ + { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ @@ -53,10 +57,6 @@ typedef struct __mavlink_gps_input_t { { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ } \ } @@ -65,7 +65,11 @@ typedef struct __mavlink_gps_input_t { "GPS_INPUT", \ 18, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ + { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ + { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ + { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ @@ -77,10 +81,6 @@ typedef struct __mavlink_gps_input_t { { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ } \ } @@ -92,24 +92,24 @@ typedef struct __mavlink_gps_input_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param gps_id ID of the GPS for multiple GPS inputs + * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. + * @param time_week_ms [ms] GPS time (from start of GPS week) + * @param time_week GPS week number + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [m] Altitude (MSL). Positive for up. + * @param hdop [m] GPS HDOP horizontal dilution of position + * @param vdop [m] GPS VDOP vertical dilution of position + * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame + * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame + * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame + * @param speed_accuracy [m/s] GPS speed accuracy + * @param horiz_accuracy [m] GPS horizontal accuracy + * @param vert_accuracy [m] GPS vertical accuracy + * @param satellites_visible Number of satellites visible. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -171,24 +171,24 @@ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param gps_id ID of the GPS for multiple GPS inputs + * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. + * @param time_week_ms [ms] GPS time (from start of GPS week) + * @param time_week GPS week number + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [m] Altitude (MSL). Positive for up. + * @param hdop [m] GPS HDOP horizontal dilution of position + * @param vdop [m] GPS VDOP vertical dilution of position + * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame + * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame + * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame + * @param speed_accuracy [m/s] GPS speed accuracy + * @param horiz_accuracy [m] GPS horizontal accuracy + * @param vert_accuracy [m] GPS vertical accuracy + * @param satellites_visible Number of satellites visible. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -276,24 +276,24 @@ static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint * @brief Send a gps_input message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param gps_id ID of the GPS for multiple GPS inputs + * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. + * @param time_week_ms [ms] GPS time (from start of GPS week) + * @param time_week GPS week number + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [m] Altitude (MSL). Positive for up. + * @param hdop [m] GPS HDOP horizontal dilution of position + * @param vdop [m] GPS VDOP vertical dilution of position + * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame + * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame + * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame + * @param speed_accuracy [m/s] GPS speed accuracy + * @param horiz_accuracy [m] GPS horizontal accuracy + * @param vert_accuracy [m] GPS vertical accuracy + * @param satellites_visible Number of satellites visible. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -426,7 +426,7 @@ static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field time_usec from gps_input message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message /** * @brief Get field gps_id from gps_input message * - * @return ID of the GPS for multiple GPS inputs + * @return ID of the GPS for multiple GPS inputs */ static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* /** * @brief Get field ignore_flags from gps_input message * - * @return Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. + * @return Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. */ static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_mess /** * @brief Get field time_week_ms from gps_input message * - * @return GPS time (milliseconds from start of GPS week) + * @return [ms] GPS time (from start of GPS week) */ static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_mess /** * @brief Get field time_week from gps_input message * - * @return GPS week number + * @return GPS week number */ static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message /** * @brief Get field fix_type from gps_input message * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK */ static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t* msg) { @@ -486,7 +486,7 @@ static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t /** * @brief Get field lat from gps_input message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg) { @@ -496,7 +496,7 @@ static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg /** * @brief Get field lon from gps_input message * - * @return Longitude (WGS84), in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg) { @@ -506,7 +506,7 @@ static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg /** * @brief Get field alt from gps_input message * - * @return Altitude (AMSL, not WGS84), in m (positive for up) + * @return [m] Altitude (MSL). Positive for up. */ static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg) { @@ -516,7 +516,7 @@ static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg) /** * @brief Get field hdop from gps_input message * - * @return GPS HDOP horizontal dilution of position in m + * @return [m] GPS HDOP horizontal dilution of position */ static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg) { @@ -526,7 +526,7 @@ static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg) /** * @brief Get field vdop from gps_input message * - * @return GPS VDOP vertical dilution of position in m + * @return [m] GPS VDOP vertical dilution of position */ static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg) { @@ -536,7 +536,7 @@ static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg) /** * @brief Get field vn from gps_input message * - * @return GPS velocity in m/s in NORTH direction in earth-fixed NED frame + * @return [m/s] GPS velocity in north direction in earth-fixed NED frame */ static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg) { @@ -546,7 +546,7 @@ static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg) /** * @brief Get field ve from gps_input message * - * @return GPS velocity in m/s in EAST direction in earth-fixed NED frame + * @return [m/s] GPS velocity in east direction in earth-fixed NED frame */ static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg) { @@ -556,7 +556,7 @@ static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg) /** * @brief Get field vd from gps_input message * - * @return GPS velocity in m/s in DOWN direction in earth-fixed NED frame + * @return [m/s] GPS velocity in down direction in earth-fixed NED frame */ static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg) { @@ -566,7 +566,7 @@ static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg) /** * @brief Get field speed_accuracy from gps_input message * - * @return GPS speed accuracy in m/s + * @return [m/s] GPS speed accuracy */ static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg) { @@ -576,7 +576,7 @@ static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_messa /** * @brief Get field horiz_accuracy from gps_input message * - * @return GPS horizontal accuracy in m + * @return [m] GPS horizontal accuracy */ static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg) { @@ -586,7 +586,7 @@ static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_messa /** * @brief Get field vert_accuracy from gps_input message * - * @return GPS vertical accuracy in m + * @return [m] GPS vertical accuracy */ static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg) { @@ -596,7 +596,7 @@ static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_messag /** * @brief Get field satellites_visible from gps_input message * - * @return Number of satellites visible. + * @return Number of satellites visible. */ static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_raw_int.h b/lib/main/MAVLink/common/mavlink_msg_gps_raw_int.h index 3033b6d5fc..6e22537c93 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_raw_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_raw_int.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_GPS_RAW_INT 24 -MAVPACKED( + typedef struct __mavlink_gps_raw_int_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ -}) mavlink_gps_raw_int_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + int32_t lat; /*< [degE7] Latitude (WGS84, EGM96 ellipsoid)*/ + int32_t lon; /*< [degE7] Longitude (WGS84, EGM96 ellipsoid)*/ + int32_t alt; /*< [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ + uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/ + uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ + uint8_t fix_type; /*< GPS fix type.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ +} mavlink_gps_raw_int_t; #define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 #define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30 @@ -33,6 +33,7 @@ typedef struct __mavlink_gps_raw_int_t { "GPS_RAW_INT", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ @@ -40,7 +41,6 @@ typedef struct __mavlink_gps_raw_int_t { { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ } \ } @@ -49,6 +49,7 @@ typedef struct __mavlink_gps_raw_int_t { "GPS_RAW_INT", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ @@ -56,7 +57,6 @@ typedef struct __mavlink_gps_raw_int_t { { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ } \ } @@ -68,16 +68,16 @@ typedef struct __mavlink_gps_raw_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type GPS fix type. + * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid) + * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid) + * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type GPS fix type. + * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid) + * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid) + * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, ui * @brief Send a gps_raw_int message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type GPS fix type. + * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid) + * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid) + * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field time_usec from gps_raw_int message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_messa /** * @brief Get field fix_type from gps_raw_int message * - * @return See the GPS_FIX_TYPE enum. + * @return GPS fix type. */ static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message /** * @brief Get field lat from gps_raw_int message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84, EGM96 ellipsoid) */ static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* m /** * @brief Get field lon from gps_raw_int message * - * @return Longitude (WGS84), in degrees * 1E7 + * @return [degE7] Longitude (WGS84, EGM96 ellipsoid) */ static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* m /** * @brief Get field alt from gps_raw_int message * - * @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @return [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. */ static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* m /** * @brief Get field eph from gps_raw_int message * - * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* /** * @brief Get field epv from gps_raw_int message * - * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* /** * @brief Get field vel from gps_raw_int message * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* /** * @brief Get field cog from gps_raw_int message * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX */ static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* /** * @brief Get field satellites_visible from gps_raw_int message * - * @return Number of satellites visible. If unknown, set to 255 + * @return Number of satellites visible. If unknown, set to 255 */ static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_rtcm_data.h b/lib/main/MAVLink/common/mavlink_msg_gps_rtcm_data.h index 2d6955c4d2..393d6adb31 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_rtcm_data.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_rtcm_data.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_GPS_RTCM_DATA 233 -MAVPACKED( + typedef struct __mavlink_gps_rtcm_data_t { - uint8_t flags; /*< LSB: 1 means message is fragmented*/ - uint8_t len; /*< data length*/ - uint8_t data[180]; /*< RTCM message (may be fragmented)*/ -}) mavlink_gps_rtcm_data_t; + uint8_t flags; /*< LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.*/ + uint8_t len; /*< [bytes] data length*/ + uint8_t data[180]; /*< RTCM message (may be fragmented)*/ +} mavlink_gps_rtcm_data_t; #define MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN 182 #define MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN 182 @@ -47,9 +47,9 @@ typedef struct __mavlink_gps_rtcm_data_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param flags LSB: 1 means message is fragmented - * @param len data length - * @param data RTCM message (may be fragmented) + * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. + * @param len [bytes] data length + * @param data RTCM message (may be fragmented) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -79,9 +79,9 @@ static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param flags LSB: 1 means message is fragmented - * @param len data length - * @param data RTCM message (may be fragmented) + * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. + * @param len [bytes] data length + * @param data RTCM message (may be fragmented) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_rtcm_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -137,9 +137,9 @@ static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id, * @brief Send a gps_rtcm_data message * @param chan MAVLink channel to send the message * - * @param flags LSB: 1 means message is fragmented - * @param len data length - * @param data RTCM message (may be fragmented) + * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. + * @param len [bytes] data length + * @param data RTCM message (may be fragmented) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -208,7 +208,7 @@ static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field flags from gps_rtcm_data message * - * @return LSB: 1 means message is fragmented + * @return LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. */ static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_t* msg) { @@ -218,7 +218,7 @@ static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_ /** * @brief Get field len from gps_rtcm_data message * - * @return data length + * @return [bytes] data length */ static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(const mavlink_message_t* msg) { @@ -228,7 +228,7 @@ static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(const mavlink_message_t* /** * @brief Get field data from gps_rtcm_data message * - * @return RTCM message (may be fragmented) + * @return RTCM message (may be fragmented) */ static inline uint16_t mavlink_msg_gps_rtcm_data_get_data(const mavlink_message_t* msg, uint8_t *data) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_rtk.h b/lib/main/MAVLink/common/mavlink_msg_gps_rtk.h index 3b25c802af..abf898f2d4 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_rtk.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_rtk.h @@ -3,22 +3,22 @@ #define MAVLINK_MSG_ID_GPS_RTK 127 -MAVPACKED( + typedef struct __mavlink_gps_rtk_t { - uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ - uint32_t tow; /*< GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ - int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ - int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ -}) mavlink_gps_rtk_t; + uint32_t time_last_baseline_ms; /*< [ms] Time since boot of last baseline message received.*/ + uint32_t tow; /*< [ms] GPS Time of Week of last baseline*/ + int32_t baseline_a_mm; /*< [mm] Current baseline in ECEF x or NED north component.*/ + int32_t baseline_b_mm; /*< [mm] Current baseline in ECEF y or NED east component.*/ + int32_t baseline_c_mm; /*< [mm] Current baseline in ECEF z or NED down component.*/ + uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ + int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ + uint16_t wn; /*< GPS Week Number of last baseline*/ + uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ + uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ + uint8_t rtk_rate; /*< [Hz] Rate of baseline messages being received by GPS*/ + uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ + uint8_t baseline_coords_type; /*< Coordinate system of baseline*/ +} mavlink_gps_rtk_t; #define MAVLINK_MSG_ID_GPS_RTK_LEN 35 #define MAVLINK_MSG_ID_GPS_RTK_MIN_LEN 35 @@ -36,18 +36,18 @@ typedef struct __mavlink_gps_rtk_t { "GPS_RTK", \ 13, \ { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ } \ } #else @@ -55,18 +55,18 @@ typedef struct __mavlink_gps_rtk_t { "GPS_RTK", \ 13, \ { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ } \ } #endif @@ -77,19 +77,19 @@ typedef struct __mavlink_gps_rtk_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow [ms] GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate [Hz] Rate of baseline messages being received by GPS + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline + * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. + * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. + * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -141,19 +141,19 @@ static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t compo * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow [ms] GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate [Hz] Rate of baseline messages being received by GPS + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline + * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. + * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. + * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -231,19 +231,19 @@ static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_ * @brief Send a gps_rtk message * @param chan MAVLink channel to send the message * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow [ms] GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate [Hz] Rate of baseline messages being received by GPS + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline + * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. + * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. + * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -356,7 +356,7 @@ static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavli /** * @brief Get field time_last_baseline_ms from gps_rtk message * - * @return Time since boot of last baseline message received in ms. + * @return [ms] Time since boot of last baseline message received. */ static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavli /** * @brief Get field rtk_receiver_id from gps_rtk message * - * @return Identification of connected RTK receiver. + * @return Identification of connected RTK receiver. */ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) { @@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_mess /** * @brief Get field wn from gps_rtk message * - * @return GPS Week Number of last baseline + * @return GPS Week Number of last baseline */ static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) /** * @brief Get field tow from gps_rtk message * - * @return GPS Time of Week of last baseline + * @return [ms] GPS Time of Week of last baseline */ static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) /** * @brief Get field rtk_health from gps_rtk message * - * @return GPS-specific health report for RTK data. + * @return GPS-specific health report for RTK data. */ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) { @@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t /** * @brief Get field rtk_rate from gps_rtk message * - * @return Rate of baseline messages being received by GPS, in HZ + * @return [Hz] Rate of baseline messages being received by GPS */ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) { @@ -416,7 +416,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* /** * @brief Get field nsats from gps_rtk message * - * @return Current number of sats used for RTK calculation. + * @return Current number of sats used for RTK calculation. */ static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) { @@ -426,7 +426,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg /** * @brief Get field baseline_coords_type from gps_rtk message * - * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + * @return Coordinate system of baseline */ static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink /** * @brief Get field baseline_a_mm from gps_rtk message * - * @return Current baseline in ECEF x or NED north component in mm. + * @return [mm] Current baseline in ECEF x or NED north component. */ static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_messag /** * @brief Get field baseline_b_mm from gps_rtk message * - * @return Current baseline in ECEF y or NED east component in mm. + * @return [mm] Current baseline in ECEF y or NED east component. */ static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_messag /** * @brief Get field baseline_c_mm from gps_rtk message * - * @return Current baseline in ECEF z or NED down component in mm. + * @return [mm] Current baseline in ECEF z or NED down component. */ static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_messag /** * @brief Get field accuracy from gps_rtk message * - * @return Current estimate of baseline accuracy. + * @return Current estimate of baseline accuracy. */ static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* /** * @brief Get field iar_num_hypotheses from gps_rtk message * - * @return Current number of integer ambiguity hypotheses. + * @return Current number of integer ambiguity hypotheses. */ static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_gps_status.h b/lib/main/MAVLink/common/mavlink_msg_gps_status.h index 8511be97ce..cedd545845 100755 --- a/lib/main/MAVLink/common/mavlink_msg_gps_status.h +++ b/lib/main/MAVLink/common/mavlink_msg_gps_status.h @@ -3,15 +3,15 @@ #define MAVLINK_MSG_ID_GPS_STATUS 25 -MAVPACKED( + typedef struct __mavlink_gps_status_t { - uint8_t satellites_visible; /*< Number of satellites visible*/ - uint8_t satellite_prn[20]; /*< Global satellite ID*/ - uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ - uint8_t satellite_elevation[20]; /*< Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ - uint8_t satellite_azimuth[20]; /*< Direction of satellite, 0: 0 deg, 255: 360 deg.*/ - uint8_t satellite_snr[20]; /*< Signal to noise ratio of satellite*/ -}) mavlink_gps_status_t; + uint8_t satellites_visible; /*< Number of satellites visible*/ + uint8_t satellite_prn[20]; /*< Global satellite ID*/ + uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ + uint8_t satellite_elevation[20]; /*< [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ + uint8_t satellite_azimuth[20]; /*< [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.*/ + uint8_t satellite_snr[20]; /*< [dB] Signal to noise ratio of satellite*/ +} mavlink_gps_status_t; #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 #define MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN 101 @@ -60,12 +60,12 @@ typedef struct __mavlink_gps_status_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr [dB] Signal to noise ratio of satellite * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -101,12 +101,12 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr [dB] Signal to noise ratio of satellite * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -168,12 +168,12 @@ static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uin * @brief Send a gps_status message * @param chan MAVLink channel to send the message * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr [dB] Signal to noise ratio of satellite */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -254,7 +254,7 @@ static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field satellites_visible from gps_status message * - * @return Number of satellites visible + * @return Number of satellites visible */ static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) { @@ -264,7 +264,7 @@ static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlin /** * @brief Get field satellite_prn from gps_status message * - * @return Global satellite ID + * @return Global satellite ID */ static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) { @@ -274,7 +274,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_me /** * @brief Get field satellite_used from gps_status message * - * @return 0: Satellite not used, 1: used for localization + * @return 0: Satellite not used, 1: used for localization */ static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) { @@ -284,7 +284,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_m /** * @brief Get field satellite_elevation from gps_status message * - * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @return [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) { @@ -294,7 +294,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavl /** * @brief Get field satellite_azimuth from gps_status message * - * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + * @return [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. */ static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) { @@ -304,7 +304,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlin /** * @brief Get field satellite_snr from gps_status message * - * @return Signal to noise ratio of satellite + * @return [dB] Signal to noise ratio of satellite */ static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) { diff --git a/lib/main/MAVLink/common/mavlink_msg_heartbeat.h b/lib/main/MAVLink/common/mavlink_msg_heartbeat.h index 66020ff41f..7774a1006b 100755 --- a/lib/main/MAVLink/common/mavlink_msg_heartbeat.h +++ b/lib/main/MAVLink/common/mavlink_msg_heartbeat.h @@ -3,15 +3,15 @@ #define MAVLINK_MSG_ID_HEARTBEAT 0 -MAVPACKED( + typedef struct __mavlink_heartbeat_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/ - uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/ - uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ - uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/ - uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ -}) mavlink_heartbeat_t; + uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags*/ + uint8_t type; /*< Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.*/ + uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/ + uint8_t base_mode; /*< System mode bitmap.*/ + uint8_t system_status; /*< System status flag.*/ + uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ +} mavlink_heartbeat_t; #define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 #define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9 @@ -28,10 +28,10 @@ typedef struct __mavlink_heartbeat_t { 0, \ "HEARTBEAT", \ 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ } \ @@ -40,10 +40,10 @@ typedef struct __mavlink_heartbeat_t { #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ "HEARTBEAT", \ 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ } \ @@ -56,11 +56,11 @@ typedef struct __mavlink_heartbeat_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM + * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. + * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + * @param base_mode System mode bitmap. + * @param custom_mode A bitfield for use for autopilot-specific flags + * @param system_status System status flag. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -98,11 +98,11 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM + * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. + * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + * @param base_mode System mode bitmap. + * @param custom_mode A bitfield for use for autopilot-specific flags + * @param system_status System status flag. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -166,11 +166,11 @@ static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint * @brief Send a heartbeat message * @param chan MAVLink channel to send the message * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM + * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. + * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + * @param base_mode System mode bitmap. + * @param custom_mode A bitfield for use for autopilot-specific flags + * @param system_status System status flag. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -255,7 +255,7 @@ static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field type from heartbeat message * - * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @return Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. */ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) { @@ -265,7 +265,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms /** * @brief Get field autopilot from heartbeat message * - * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. */ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) { @@ -275,7 +275,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_ /** * @brief Get field base_mode from heartbeat message * - * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @return System mode bitmap. */ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) { @@ -285,7 +285,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_ /** * @brief Get field custom_mode from heartbeat message * - * @return A bitfield for use for autopilot-specific flags. + * @return A bitfield for use for autopilot-specific flags */ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) { @@ -295,7 +295,7 @@ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa /** * @brief Get field system_status from heartbeat message * - * @return System status flag, see MAV_STATE ENUM + * @return System status flag. */ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) { @@ -305,7 +305,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_mess /** * @brief Get field mavlink_version from heartbeat message * - * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version */ static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_high_latency.h b/lib/main/MAVLink/common/mavlink_msg_high_latency.h index 7c87e5c2d9..a0f4e84963 100755 --- a/lib/main/MAVLink/common/mavlink_msg_high_latency.h +++ b/lib/main/MAVLink/common/mavlink_msg_high_latency.h @@ -3,33 +3,33 @@ #define MAVLINK_MSG_ID_HIGH_LATENCY 234 -MAVPACKED( + typedef struct __mavlink_high_latency_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - int32_t latitude; /*< Latitude, expressed as degrees * 1E7*/ - int32_t longitude; /*< Longitude, expressed as degrees * 1E7*/ - int16_t roll; /*< roll (centidegrees)*/ - int16_t pitch; /*< pitch (centidegrees)*/ - uint16_t heading; /*< heading (centidegrees)*/ - int16_t heading_sp; /*< heading setpoint (centidegrees)*/ - int16_t altitude_amsl; /*< Altitude above mean sea level (meters)*/ - int16_t altitude_sp; /*< Altitude setpoint relative to the home position (meters)*/ - uint16_t wp_distance; /*< distance to target (meters)*/ - uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ - int8_t throttle; /*< throttle (percentage)*/ - uint8_t airspeed; /*< airspeed (m/s)*/ - uint8_t airspeed_sp; /*< airspeed setpoint (m/s)*/ - uint8_t groundspeed; /*< groundspeed (m/s)*/ - int8_t climb_rate; /*< climb rate (m/s)*/ - uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to 255*/ - uint8_t gps_fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t battery_remaining; /*< Remaining battery (percentage)*/ - int8_t temperature; /*< Autopilot temperature (degrees C)*/ - int8_t temperature_air; /*< Air temperature (degrees C) from airspeed sensor*/ - uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/ - uint8_t wp_num; /*< current waypoint number*/ -}) mavlink_high_latency_t; + uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ + int32_t latitude; /*< [degE7] Latitude*/ + int32_t longitude; /*< [degE7] Longitude*/ + int16_t roll; /*< [cdeg] roll*/ + int16_t pitch; /*< [cdeg] pitch*/ + uint16_t heading; /*< [cdeg] heading*/ + int16_t heading_sp; /*< [cdeg] heading setpoint*/ + int16_t altitude_amsl; /*< [m] Altitude above mean sea level*/ + int16_t altitude_sp; /*< [m] Altitude setpoint relative to the home position*/ + uint16_t wp_distance; /*< [m] distance to target*/ + uint8_t base_mode; /*< Bitmap of enabled system modes.*/ + uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ + int8_t throttle; /*< [%] throttle (percentage)*/ + uint8_t airspeed; /*< [m/s] airspeed*/ + uint8_t airspeed_sp; /*< [m/s] airspeed setpoint*/ + uint8_t groundspeed; /*< [m/s] groundspeed*/ + int8_t climb_rate; /*< [m/s] climb rate*/ + uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to 255*/ + uint8_t gps_fix_type; /*< GPS Fix type.*/ + uint8_t battery_remaining; /*< [%] Remaining battery (percentage)*/ + int8_t temperature; /*< [degC] Autopilot temperature (degrees C)*/ + int8_t temperature_air; /*< [degC] Air temperature (degrees C) from airspeed sensor*/ + uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/ + uint8_t wp_num; /*< current waypoint number*/ +} mavlink_high_latency_t; #define MAVLINK_MSG_ID_HIGH_LATENCY_LEN 40 #define MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN 40 @@ -46,19 +46,18 @@ typedef struct __mavlink_high_latency_t { 234, \ "HIGH_LATENCY", \ 24, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ + { { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ + { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ @@ -70,25 +69,25 @@ typedef struct __mavlink_high_latency_t { { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ + { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ "HIGH_LATENCY", \ 24, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ + { { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ + { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ @@ -100,6 +99,7 @@ typedef struct __mavlink_high_latency_t { { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ + { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ } \ } #endif @@ -110,30 +110,30 @@ typedef struct __mavlink_high_latency_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) + * @param base_mode Bitmap of enabled system modes. + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @param roll [cdeg] roll + * @param pitch [cdeg] pitch + * @param heading [cdeg] heading + * @param throttle [%] throttle (percentage) + * @param heading_sp [cdeg] heading setpoint + * @param latitude [degE7] Latitude + * @param longitude [degE7] Longitude + * @param altitude_amsl [m] Altitude above mean sea level + * @param altitude_sp [m] Altitude setpoint relative to the home position + * @param airspeed [m/s] airspeed + * @param airspeed_sp [m/s] airspeed setpoint + * @param groundspeed [m/s] groundspeed + * @param climb_rate [m/s] climb rate + * @param gps_nsat Number of satellites visible. If unknown, set to 255 + * @param gps_fix_type GPS Fix type. + * @param battery_remaining [%] Remaining battery (percentage) + * @param temperature [degC] Autopilot temperature (degrees C) + * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor + * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) + * @param wp_num current waypoint number + * @param wp_distance [m] distance to target * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -207,30 +207,30 @@ static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) + * @param base_mode Bitmap of enabled system modes. + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @param roll [cdeg] roll + * @param pitch [cdeg] pitch + * @param heading [cdeg] heading + * @param throttle [%] throttle (percentage) + * @param heading_sp [cdeg] heading setpoint + * @param latitude [degE7] Latitude + * @param longitude [degE7] Longitude + * @param altitude_amsl [m] Altitude above mean sea level + * @param altitude_sp [m] Altitude setpoint relative to the home position + * @param airspeed [m/s] airspeed + * @param airspeed_sp [m/s] airspeed setpoint + * @param groundspeed [m/s] groundspeed + * @param climb_rate [m/s] climb rate + * @param gps_nsat Number of satellites visible. If unknown, set to 255 + * @param gps_fix_type GPS Fix type. + * @param battery_remaining [%] Remaining battery (percentage) + * @param temperature [degC] Autopilot temperature (degrees C) + * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor + * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) + * @param wp_num current waypoint number + * @param wp_distance [m] distance to target * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -330,30 +330,30 @@ static inline uint16_t mavlink_msg_high_latency_encode_chan(uint8_t system_id, u * @brief Send a high_latency message * @param chan MAVLink channel to send the message * - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) + * @param base_mode Bitmap of enabled system modes. + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @param roll [cdeg] roll + * @param pitch [cdeg] pitch + * @param heading [cdeg] heading + * @param throttle [%] throttle (percentage) + * @param heading_sp [cdeg] heading setpoint + * @param latitude [degE7] Latitude + * @param longitude [degE7] Longitude + * @param altitude_amsl [m] Altitude above mean sea level + * @param altitude_sp [m] Altitude setpoint relative to the home position + * @param airspeed [m/s] airspeed + * @param airspeed_sp [m/s] airspeed setpoint + * @param groundspeed [m/s] groundspeed + * @param climb_rate [m/s] climb rate + * @param gps_nsat Number of satellites visible. If unknown, set to 255 + * @param gps_fix_type GPS Fix type. + * @param battery_remaining [%] Remaining battery (percentage) + * @param temperature [degC] Autopilot temperature (degrees C) + * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor + * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) + * @param wp_num current waypoint number + * @param wp_distance [m] distance to target */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -510,7 +510,7 @@ static inline void mavlink_msg_high_latency_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field base_mode from high_latency message * - * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @return Bitmap of enabled system modes. */ static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg) { @@ -520,7 +520,7 @@ static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_messa /** * @brief Get field custom_mode from high_latency message * - * @return A bitfield for use for autopilot-specific flags. + * @return A bitfield for use for autopilot-specific flags. */ static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_message_t* msg) { @@ -530,7 +530,7 @@ static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_me /** * @brief Get field landed_state from high_latency message * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. */ static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_message_t* msg) { @@ -540,7 +540,7 @@ static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_me /** * @brief Get field roll from high_latency message * - * @return roll (centidegrees) + * @return [cdeg] roll */ static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg) { @@ -550,7 +550,7 @@ static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* /** * @brief Get field pitch from high_latency message * - * @return pitch (centidegrees) + * @return [cdeg] pitch */ static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg) { @@ -560,7 +560,7 @@ static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t /** * @brief Get field heading from high_latency message * - * @return heading (centidegrees) + * @return [cdeg] heading */ static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg) { @@ -570,7 +570,7 @@ static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_messag /** * @brief Get field throttle from high_latency message * - * @return throttle (percentage) + * @return [%] throttle (percentage) */ static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg) { @@ -580,7 +580,7 @@ static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message /** * @brief Get field heading_sp from high_latency message * - * @return heading setpoint (centidegrees) + * @return [cdeg] heading setpoint */ static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg) { @@ -590,7 +590,7 @@ static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_mess /** * @brief Get field latitude from high_latency message * - * @return Latitude, expressed as degrees * 1E7 + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg) { @@ -600,7 +600,7 @@ static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_messag /** * @brief Get field longitude from high_latency message * - * @return Longitude, expressed as degrees * 1E7 + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg) { @@ -610,7 +610,7 @@ static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_messa /** * @brief Get field altitude_amsl from high_latency message * - * @return Altitude above mean sea level (meters) + * @return [m] Altitude above mean sea level */ static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg) { @@ -620,7 +620,7 @@ static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_m /** * @brief Get field altitude_sp from high_latency message * - * @return Altitude setpoint relative to the home position (meters) + * @return [m] Altitude setpoint relative to the home position */ static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg) { @@ -630,7 +630,7 @@ static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_mes /** * @brief Get field airspeed from high_latency message * - * @return airspeed (m/s) + * @return [m/s] airspeed */ static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg) { @@ -640,7 +640,7 @@ static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_messag /** * @brief Get field airspeed_sp from high_latency message * - * @return airspeed setpoint (m/s) + * @return [m/s] airspeed setpoint */ static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg) { @@ -650,7 +650,7 @@ static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_mes /** * @brief Get field groundspeed from high_latency message * - * @return groundspeed (m/s) + * @return [m/s] groundspeed */ static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg) { @@ -660,7 +660,7 @@ static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_mes /** * @brief Get field climb_rate from high_latency message * - * @return climb rate (m/s) + * @return [m/s] climb rate */ static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg) { @@ -670,7 +670,7 @@ static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_messa /** * @brief Get field gps_nsat from high_latency message * - * @return Number of satellites visible. If unknown, set to 255 + * @return Number of satellites visible. If unknown, set to 255 */ static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_message_t* msg) { @@ -680,7 +680,7 @@ static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_messag /** * @brief Get field gps_fix_type from high_latency message * - * @return See the GPS_FIX_TYPE enum. + * @return GPS Fix type. */ static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg) { @@ -690,7 +690,7 @@ static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_me /** * @brief Get field battery_remaining from high_latency message * - * @return Remaining battery (percentage) + * @return [%] Remaining battery (percentage) */ static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg) { @@ -700,7 +700,7 @@ static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavli /** * @brief Get field temperature from high_latency message * - * @return Autopilot temperature (degrees C) + * @return [degC] Autopilot temperature (degrees C) */ static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg) { @@ -710,7 +710,7 @@ static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_mess /** * @brief Get field temperature_air from high_latency message * - * @return Air temperature (degrees C) from airspeed sensor + * @return [degC] Air temperature (degrees C) from airspeed sensor */ static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg) { @@ -720,7 +720,7 @@ static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_ /** * @brief Get field failsafe from high_latency message * - * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) + * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) */ static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_message_t* msg) { @@ -730,7 +730,7 @@ static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_messag /** * @brief Get field wp_num from high_latency message * - * @return current waypoint number + * @return current waypoint number */ static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_t* msg) { @@ -740,7 +740,7 @@ static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_ /** * @brief Get field wp_distance from high_latency message * - * @return distance to target (meters) + * @return [m] distance to target */ static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_high_latency2.h b/lib/main/MAVLink/common/mavlink_msg_high_latency2.h new file mode 100644 index 0000000000..3de15a7101 --- /dev/null +++ b/lib/main/MAVLink/common/mavlink_msg_high_latency2.h @@ -0,0 +1,863 @@ +#pragma once +// MESSAGE HIGH_LATENCY2 PACKING + +#define MAVLINK_MSG_ID_HIGH_LATENCY2 235 + + +typedef struct __mavlink_high_latency2_t { + uint32_t timestamp; /*< [ms] Timestamp (milliseconds since boot or Unix epoch)*/ + int32_t latitude; /*< [degE7] Latitude*/ + int32_t longitude; /*< [degE7] Longitude*/ + uint16_t custom_mode; /*< A bitfield for use for autopilot-specific flags (2 byte version).*/ + int16_t altitude; /*< [m] Altitude above mean sea level*/ + int16_t target_altitude; /*< [m] Altitude setpoint*/ + uint16_t target_distance; /*< [dam] Distance to target waypoint or position*/ + uint16_t wp_num; /*< Current waypoint number*/ + uint16_t failure_flags; /*< Bitmap of failure flags.*/ + uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc.)*/ + uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/ + uint8_t heading; /*< [deg/2] Heading*/ + uint8_t target_heading; /*< [deg/2] Heading setpoint*/ + uint8_t throttle; /*< [%] Throttle*/ + uint8_t airspeed; /*< [m/s*5] Airspeed*/ + uint8_t airspeed_sp; /*< [m/s*5] Airspeed setpoint*/ + uint8_t groundspeed; /*< [m/s*5] Groundspeed*/ + uint8_t windspeed; /*< [m/s*5] Windspeed*/ + uint8_t wind_heading; /*< [deg/2] Wind heading*/ + uint8_t eph; /*< [dm] Maximum error horizontal position since last message*/ + uint8_t epv; /*< [dm] Maximum error vertical position since last message*/ + int8_t temperature_air; /*< [degC] Air temperature from airspeed sensor*/ + int8_t climb_rate; /*< [dm/s] Maximum climb rate magnitude since last message*/ + int8_t battery; /*< [%] Battery level (-1 if field not provided).*/ + int8_t custom0; /*< Field for custom payload.*/ + int8_t custom1; /*< Field for custom payload.*/ + int8_t custom2; /*< Field for custom payload.*/ +} mavlink_high_latency2_t; + +#define MAVLINK_MSG_ID_HIGH_LATENCY2_LEN 42 +#define MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN 42 +#define MAVLINK_MSG_ID_235_LEN 42 +#define MAVLINK_MSG_ID_235_MIN_LEN 42 + +#define MAVLINK_MSG_ID_HIGH_LATENCY2_CRC 179 +#define MAVLINK_MSG_ID_235_CRC 179 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \ + 235, \ + "HIGH_LATENCY2", \ + 27, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \ + { "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \ + { "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \ + { "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \ + { "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \ + { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \ + { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \ + { "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \ + { "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \ + { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \ + { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \ + { "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \ + { "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \ + { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \ + { "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \ + { "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \ + { "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \ + "HIGH_LATENCY2", \ + 27, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \ + { "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \ + { "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \ + { "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \ + { "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \ + { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \ + { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \ + { "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \ + { "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \ + { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \ + { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \ + { "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \ + { "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \ + { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \ + { "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \ + { "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \ + { "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \ + } \ +} +#endif + +/** + * @brief Pack a high_latency2 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch) + * @param type Type of the MAV (quadrotor, helicopter, etc.) + * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version). + * @param latitude [degE7] Latitude + * @param longitude [degE7] Longitude + * @param altitude [m] Altitude above mean sea level + * @param target_altitude [m] Altitude setpoint + * @param heading [deg/2] Heading + * @param target_heading [deg/2] Heading setpoint + * @param target_distance [dam] Distance to target waypoint or position + * @param throttle [%] Throttle + * @param airspeed [m/s*5] Airspeed + * @param airspeed_sp [m/s*5] Airspeed setpoint + * @param groundspeed [m/s*5] Groundspeed + * @param windspeed [m/s*5] Windspeed + * @param wind_heading [deg/2] Wind heading + * @param eph [dm] Maximum error horizontal position since last message + * @param epv [dm] Maximum error vertical position since last message + * @param temperature_air [degC] Air temperature from airspeed sensor + * @param climb_rate [dm/s] Maximum climb rate magnitude since last message + * @param battery [%] Battery level (-1 if field not provided). + * @param wp_num Current waypoint number + * @param failure_flags Bitmap of failure flags. + * @param custom0 Field for custom payload. + * @param custom1 Field for custom payload. + * @param custom2 Field for custom payload. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_high_latency2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN]; + _mav_put_uint32_t(buf, 0, timestamp); + _mav_put_int32_t(buf, 4, latitude); + _mav_put_int32_t(buf, 8, longitude); + _mav_put_uint16_t(buf, 12, custom_mode); + _mav_put_int16_t(buf, 14, altitude); + _mav_put_int16_t(buf, 16, target_altitude); + _mav_put_uint16_t(buf, 18, target_distance); + _mav_put_uint16_t(buf, 20, wp_num); + _mav_put_uint16_t(buf, 22, failure_flags); + _mav_put_uint8_t(buf, 24, type); + _mav_put_uint8_t(buf, 25, autopilot); + _mav_put_uint8_t(buf, 26, heading); + _mav_put_uint8_t(buf, 27, target_heading); + _mav_put_uint8_t(buf, 28, throttle); + _mav_put_uint8_t(buf, 29, airspeed); + _mav_put_uint8_t(buf, 30, airspeed_sp); + _mav_put_uint8_t(buf, 31, groundspeed); + _mav_put_uint8_t(buf, 32, windspeed); + _mav_put_uint8_t(buf, 33, wind_heading); + _mav_put_uint8_t(buf, 34, eph); + _mav_put_uint8_t(buf, 35, epv); + _mav_put_int8_t(buf, 36, temperature_air); + _mav_put_int8_t(buf, 37, climb_rate); + _mav_put_int8_t(buf, 38, battery); + _mav_put_int8_t(buf, 39, custom0); + _mav_put_int8_t(buf, 40, custom1); + _mav_put_int8_t(buf, 41, custom2); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); +#else + mavlink_high_latency2_t packet; + packet.timestamp = timestamp; + packet.latitude = latitude; + packet.longitude = longitude; + packet.custom_mode = custom_mode; + packet.altitude = altitude; + packet.target_altitude = target_altitude; + packet.target_distance = target_distance; + packet.wp_num = wp_num; + packet.failure_flags = failure_flags; + packet.type = type; + packet.autopilot = autopilot; + packet.heading = heading; + packet.target_heading = target_heading; + packet.throttle = throttle; + packet.airspeed = airspeed; + packet.airspeed_sp = airspeed_sp; + packet.groundspeed = groundspeed; + packet.windspeed = windspeed; + packet.wind_heading = wind_heading; + packet.eph = eph; + packet.epv = epv; + packet.temperature_air = temperature_air; + packet.climb_rate = climb_rate; + packet.battery = battery; + packet.custom0 = custom0; + packet.custom1 = custom1; + packet.custom2 = custom2; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY2; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +} + +/** + * @brief Pack a high_latency2 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch) + * @param type Type of the MAV (quadrotor, helicopter, etc.) + * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version). + * @param latitude [degE7] Latitude + * @param longitude [degE7] Longitude + * @param altitude [m] Altitude above mean sea level + * @param target_altitude [m] Altitude setpoint + * @param heading [deg/2] Heading + * @param target_heading [deg/2] Heading setpoint + * @param target_distance [dam] Distance to target waypoint or position + * @param throttle [%] Throttle + * @param airspeed [m/s*5] Airspeed + * @param airspeed_sp [m/s*5] Airspeed setpoint + * @param groundspeed [m/s*5] Groundspeed + * @param windspeed [m/s*5] Windspeed + * @param wind_heading [deg/2] Wind heading + * @param eph [dm] Maximum error horizontal position since last message + * @param epv [dm] Maximum error vertical position since last message + * @param temperature_air [degC] Air temperature from airspeed sensor + * @param climb_rate [dm/s] Maximum climb rate magnitude since last message + * @param battery [%] Battery level (-1 if field not provided). + * @param wp_num Current waypoint number + * @param failure_flags Bitmap of failure flags. + * @param custom0 Field for custom payload. + * @param custom1 Field for custom payload. + * @param custom2 Field for custom payload. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_high_latency2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t timestamp,uint8_t type,uint8_t autopilot,uint16_t custom_mode,int32_t latitude,int32_t longitude,int16_t altitude,int16_t target_altitude,uint8_t heading,uint8_t target_heading,uint16_t target_distance,uint8_t throttle,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,uint8_t windspeed,uint8_t wind_heading,uint8_t eph,uint8_t epv,int8_t temperature_air,int8_t climb_rate,int8_t battery,uint16_t wp_num,uint16_t failure_flags,int8_t custom0,int8_t custom1,int8_t custom2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN]; + _mav_put_uint32_t(buf, 0, timestamp); + _mav_put_int32_t(buf, 4, latitude); + _mav_put_int32_t(buf, 8, longitude); + _mav_put_uint16_t(buf, 12, custom_mode); + _mav_put_int16_t(buf, 14, altitude); + _mav_put_int16_t(buf, 16, target_altitude); + _mav_put_uint16_t(buf, 18, target_distance); + _mav_put_uint16_t(buf, 20, wp_num); + _mav_put_uint16_t(buf, 22, failure_flags); + _mav_put_uint8_t(buf, 24, type); + _mav_put_uint8_t(buf, 25, autopilot); + _mav_put_uint8_t(buf, 26, heading); + _mav_put_uint8_t(buf, 27, target_heading); + _mav_put_uint8_t(buf, 28, throttle); + _mav_put_uint8_t(buf, 29, airspeed); + _mav_put_uint8_t(buf, 30, airspeed_sp); + _mav_put_uint8_t(buf, 31, groundspeed); + _mav_put_uint8_t(buf, 32, windspeed); + _mav_put_uint8_t(buf, 33, wind_heading); + _mav_put_uint8_t(buf, 34, eph); + _mav_put_uint8_t(buf, 35, epv); + _mav_put_int8_t(buf, 36, temperature_air); + _mav_put_int8_t(buf, 37, climb_rate); + _mav_put_int8_t(buf, 38, battery); + _mav_put_int8_t(buf, 39, custom0); + _mav_put_int8_t(buf, 40, custom1); + _mav_put_int8_t(buf, 41, custom2); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); +#else + mavlink_high_latency2_t packet; + packet.timestamp = timestamp; + packet.latitude = latitude; + packet.longitude = longitude; + packet.custom_mode = custom_mode; + packet.altitude = altitude; + packet.target_altitude = target_altitude; + packet.target_distance = target_distance; + packet.wp_num = wp_num; + packet.failure_flags = failure_flags; + packet.type = type; + packet.autopilot = autopilot; + packet.heading = heading; + packet.target_heading = target_heading; + packet.throttle = throttle; + packet.airspeed = airspeed; + packet.airspeed_sp = airspeed_sp; + packet.groundspeed = groundspeed; + packet.windspeed = windspeed; + packet.wind_heading = wind_heading; + packet.eph = eph; + packet.epv = epv; + packet.temperature_air = temperature_air; + packet.climb_rate = climb_rate; + packet.battery = battery; + packet.custom0 = custom0; + packet.custom1 = custom1; + packet.custom2 = custom2; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY2; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +} + +/** + * @brief Encode a high_latency2 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param high_latency2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_high_latency2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency2_t* high_latency2) +{ + return mavlink_msg_high_latency2_pack(system_id, component_id, msg, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2); +} + +/** + * @brief Encode a high_latency2 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param high_latency2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_high_latency2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency2_t* high_latency2) +{ + return mavlink_msg_high_latency2_pack_chan(system_id, component_id, chan, msg, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2); +} + +/** + * @brief Send a high_latency2 message + * @param chan MAVLink channel to send the message + * + * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch) + * @param type Type of the MAV (quadrotor, helicopter, etc.) + * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version). + * @param latitude [degE7] Latitude + * @param longitude [degE7] Longitude + * @param altitude [m] Altitude above mean sea level + * @param target_altitude [m] Altitude setpoint + * @param heading [deg/2] Heading + * @param target_heading [deg/2] Heading setpoint + * @param target_distance [dam] Distance to target waypoint or position + * @param throttle [%] Throttle + * @param airspeed [m/s*5] Airspeed + * @param airspeed_sp [m/s*5] Airspeed setpoint + * @param groundspeed [m/s*5] Groundspeed + * @param windspeed [m/s*5] Windspeed + * @param wind_heading [deg/2] Wind heading + * @param eph [dm] Maximum error horizontal position since last message + * @param epv [dm] Maximum error vertical position since last message + * @param temperature_air [degC] Air temperature from airspeed sensor + * @param climb_rate [dm/s] Maximum climb rate magnitude since last message + * @param battery [%] Battery level (-1 if field not provided). + * @param wp_num Current waypoint number + * @param failure_flags Bitmap of failure flags. + * @param custom0 Field for custom payload. + * @param custom1 Field for custom payload. + * @param custom2 Field for custom payload. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_high_latency2_send(mavlink_channel_t chan, uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN]; + _mav_put_uint32_t(buf, 0, timestamp); + _mav_put_int32_t(buf, 4, latitude); + _mav_put_int32_t(buf, 8, longitude); + _mav_put_uint16_t(buf, 12, custom_mode); + _mav_put_int16_t(buf, 14, altitude); + _mav_put_int16_t(buf, 16, target_altitude); + _mav_put_uint16_t(buf, 18, target_distance); + _mav_put_uint16_t(buf, 20, wp_num); + _mav_put_uint16_t(buf, 22, failure_flags); + _mav_put_uint8_t(buf, 24, type); + _mav_put_uint8_t(buf, 25, autopilot); + _mav_put_uint8_t(buf, 26, heading); + _mav_put_uint8_t(buf, 27, target_heading); + _mav_put_uint8_t(buf, 28, throttle); + _mav_put_uint8_t(buf, 29, airspeed); + _mav_put_uint8_t(buf, 30, airspeed_sp); + _mav_put_uint8_t(buf, 31, groundspeed); + _mav_put_uint8_t(buf, 32, windspeed); + _mav_put_uint8_t(buf, 33, wind_heading); + _mav_put_uint8_t(buf, 34, eph); + _mav_put_uint8_t(buf, 35, epv); + _mav_put_int8_t(buf, 36, temperature_air); + _mav_put_int8_t(buf, 37, climb_rate); + _mav_put_int8_t(buf, 38, battery); + _mav_put_int8_t(buf, 39, custom0); + _mav_put_int8_t(buf, 40, custom1); + _mav_put_int8_t(buf, 41, custom2); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, buf, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +#else + mavlink_high_latency2_t packet; + packet.timestamp = timestamp; + packet.latitude = latitude; + packet.longitude = longitude; + packet.custom_mode = custom_mode; + packet.altitude = altitude; + packet.target_altitude = target_altitude; + packet.target_distance = target_distance; + packet.wp_num = wp_num; + packet.failure_flags = failure_flags; + packet.type = type; + packet.autopilot = autopilot; + packet.heading = heading; + packet.target_heading = target_heading; + packet.throttle = throttle; + packet.airspeed = airspeed; + packet.airspeed_sp = airspeed_sp; + packet.groundspeed = groundspeed; + packet.windspeed = windspeed; + packet.wind_heading = wind_heading; + packet.eph = eph; + packet.epv = epv; + packet.temperature_air = temperature_air; + packet.climb_rate = climb_rate; + packet.battery = battery; + packet.custom0 = custom0; + packet.custom1 = custom1; + packet.custom2 = custom2; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +#endif +} + +/** + * @brief Send a high_latency2 message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_high_latency2_send_struct(mavlink_channel_t chan, const mavlink_high_latency2_t* high_latency2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_high_latency2_send(chan, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)high_latency2, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +#endif +} + +#if MAVLINK_MSG_ID_HIGH_LATENCY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_high_latency2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, timestamp); + _mav_put_int32_t(buf, 4, latitude); + _mav_put_int32_t(buf, 8, longitude); + _mav_put_uint16_t(buf, 12, custom_mode); + _mav_put_int16_t(buf, 14, altitude); + _mav_put_int16_t(buf, 16, target_altitude); + _mav_put_uint16_t(buf, 18, target_distance); + _mav_put_uint16_t(buf, 20, wp_num); + _mav_put_uint16_t(buf, 22, failure_flags); + _mav_put_uint8_t(buf, 24, type); + _mav_put_uint8_t(buf, 25, autopilot); + _mav_put_uint8_t(buf, 26, heading); + _mav_put_uint8_t(buf, 27, target_heading); + _mav_put_uint8_t(buf, 28, throttle); + _mav_put_uint8_t(buf, 29, airspeed); + _mav_put_uint8_t(buf, 30, airspeed_sp); + _mav_put_uint8_t(buf, 31, groundspeed); + _mav_put_uint8_t(buf, 32, windspeed); + _mav_put_uint8_t(buf, 33, wind_heading); + _mav_put_uint8_t(buf, 34, eph); + _mav_put_uint8_t(buf, 35, epv); + _mav_put_int8_t(buf, 36, temperature_air); + _mav_put_int8_t(buf, 37, climb_rate); + _mav_put_int8_t(buf, 38, battery); + _mav_put_int8_t(buf, 39, custom0); + _mav_put_int8_t(buf, 40, custom1); + _mav_put_int8_t(buf, 41, custom2); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, buf, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +#else + mavlink_high_latency2_t *packet = (mavlink_high_latency2_t *)msgbuf; + packet->timestamp = timestamp; + packet->latitude = latitude; + packet->longitude = longitude; + packet->custom_mode = custom_mode; + packet->altitude = altitude; + packet->target_altitude = target_altitude; + packet->target_distance = target_distance; + packet->wp_num = wp_num; + packet->failure_flags = failure_flags; + packet->type = type; + packet->autopilot = autopilot; + packet->heading = heading; + packet->target_heading = target_heading; + packet->throttle = throttle; + packet->airspeed = airspeed; + packet->airspeed_sp = airspeed_sp; + packet->groundspeed = groundspeed; + packet->windspeed = windspeed; + packet->wind_heading = wind_heading; + packet->eph = eph; + packet->epv = epv; + packet->temperature_air = temperature_air; + packet->climb_rate = climb_rate; + packet->battery = battery; + packet->custom0 = custom0; + packet->custom1 = custom1; + packet->custom2 = custom2; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); +#endif +} +#endif + +#endif + +// MESSAGE HIGH_LATENCY2 UNPACKING + + +/** + * @brief Get field timestamp from high_latency2 message + * + * @return [ms] Timestamp (milliseconds since boot or Unix epoch) + */ +static inline uint32_t mavlink_msg_high_latency2_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field type from high_latency2 message + * + * @return Type of the MAV (quadrotor, helicopter, etc.) + */ +static inline uint8_t mavlink_msg_high_latency2_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field autopilot from high_latency2 message + * + * @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. + */ +static inline uint8_t mavlink_msg_high_latency2_get_autopilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field custom_mode from high_latency2 message + * + * @return A bitfield for use for autopilot-specific flags (2 byte version). + */ +static inline uint16_t mavlink_msg_high_latency2_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field latitude from high_latency2 message + * + * @return [degE7] Latitude + */ +static inline int32_t mavlink_msg_high_latency2_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field longitude from high_latency2 message + * + * @return [degE7] Longitude + */ +static inline int32_t mavlink_msg_high_latency2_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field altitude from high_latency2 message + * + * @return [m] Altitude above mean sea level + */ +static inline int16_t mavlink_msg_high_latency2_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field target_altitude from high_latency2 message + * + * @return [m] Altitude setpoint + */ +static inline int16_t mavlink_msg_high_latency2_get_target_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field heading from high_latency2 message + * + * @return [deg/2] Heading + */ +static inline uint8_t mavlink_msg_high_latency2_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field target_heading from high_latency2 message + * + * @return [deg/2] Heading setpoint + */ +static inline uint8_t mavlink_msg_high_latency2_get_target_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 27); +} + +/** + * @brief Get field target_distance from high_latency2 message + * + * @return [dam] Distance to target waypoint or position + */ +static inline uint16_t mavlink_msg_high_latency2_get_target_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field throttle from high_latency2 message + * + * @return [%] Throttle + */ +static inline uint8_t mavlink_msg_high_latency2_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field airspeed from high_latency2 message + * + * @return [m/s*5] Airspeed + */ +static inline uint8_t mavlink_msg_high_latency2_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Get field airspeed_sp from high_latency2 message + * + * @return [m/s*5] Airspeed setpoint + */ +static inline uint8_t mavlink_msg_high_latency2_get_airspeed_sp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field groundspeed from high_latency2 message + * + * @return [m/s*5] Groundspeed + */ +static inline uint8_t mavlink_msg_high_latency2_get_groundspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field windspeed from high_latency2 message + * + * @return [m/s*5] Windspeed + */ +static inline uint8_t mavlink_msg_high_latency2_get_windspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field wind_heading from high_latency2 message + * + * @return [deg/2] Wind heading + */ +static inline uint8_t mavlink_msg_high_latency2_get_wind_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field eph from high_latency2 message + * + * @return [dm] Maximum error horizontal position since last message + */ +static inline uint8_t mavlink_msg_high_latency2_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field epv from high_latency2 message + * + * @return [dm] Maximum error vertical position since last message + */ +static inline uint8_t mavlink_msg_high_latency2_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field temperature_air from high_latency2 message + * + * @return [degC] Air temperature from airspeed sensor + */ +static inline int8_t mavlink_msg_high_latency2_get_temperature_air(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 36); +} + +/** + * @brief Get field climb_rate from high_latency2 message + * + * @return [dm/s] Maximum climb rate magnitude since last message + */ +static inline int8_t mavlink_msg_high_latency2_get_climb_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 37); +} + +/** + * @brief Get field battery from high_latency2 message + * + * @return [%] Battery level (-1 if field not provided). + */ +static inline int8_t mavlink_msg_high_latency2_get_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 38); +} + +/** + * @brief Get field wp_num from high_latency2 message + * + * @return Current waypoint number + */ +static inline uint16_t mavlink_msg_high_latency2_get_wp_num(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field failure_flags from high_latency2 message + * + * @return Bitmap of failure flags. + */ +static inline uint16_t mavlink_msg_high_latency2_get_failure_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field custom0 from high_latency2 message + * + * @return Field for custom payload. + */ +static inline int8_t mavlink_msg_high_latency2_get_custom0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 39); +} + +/** + * @brief Get field custom1 from high_latency2 message + * + * @return Field for custom payload. + */ +static inline int8_t mavlink_msg_high_latency2_get_custom1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 40); +} + +/** + * @brief Get field custom2 from high_latency2 message + * + * @return Field for custom payload. + */ +static inline int8_t mavlink_msg_high_latency2_get_custom2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 41); +} + +/** + * @brief Decode a high_latency2 message into a struct + * + * @param msg The message to decode + * @param high_latency2 C-struct to decode the message contents into + */ +static inline void mavlink_msg_high_latency2_decode(const mavlink_message_t* msg, mavlink_high_latency2_t* high_latency2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + high_latency2->timestamp = mavlink_msg_high_latency2_get_timestamp(msg); + high_latency2->latitude = mavlink_msg_high_latency2_get_latitude(msg); + high_latency2->longitude = mavlink_msg_high_latency2_get_longitude(msg); + high_latency2->custom_mode = mavlink_msg_high_latency2_get_custom_mode(msg); + high_latency2->altitude = mavlink_msg_high_latency2_get_altitude(msg); + high_latency2->target_altitude = mavlink_msg_high_latency2_get_target_altitude(msg); + high_latency2->target_distance = mavlink_msg_high_latency2_get_target_distance(msg); + high_latency2->wp_num = mavlink_msg_high_latency2_get_wp_num(msg); + high_latency2->failure_flags = mavlink_msg_high_latency2_get_failure_flags(msg); + high_latency2->type = mavlink_msg_high_latency2_get_type(msg); + high_latency2->autopilot = mavlink_msg_high_latency2_get_autopilot(msg); + high_latency2->heading = mavlink_msg_high_latency2_get_heading(msg); + high_latency2->target_heading = mavlink_msg_high_latency2_get_target_heading(msg); + high_latency2->throttle = mavlink_msg_high_latency2_get_throttle(msg); + high_latency2->airspeed = mavlink_msg_high_latency2_get_airspeed(msg); + high_latency2->airspeed_sp = mavlink_msg_high_latency2_get_airspeed_sp(msg); + high_latency2->groundspeed = mavlink_msg_high_latency2_get_groundspeed(msg); + high_latency2->windspeed = mavlink_msg_high_latency2_get_windspeed(msg); + high_latency2->wind_heading = mavlink_msg_high_latency2_get_wind_heading(msg); + high_latency2->eph = mavlink_msg_high_latency2_get_eph(msg); + high_latency2->epv = mavlink_msg_high_latency2_get_epv(msg); + high_latency2->temperature_air = mavlink_msg_high_latency2_get_temperature_air(msg); + high_latency2->climb_rate = mavlink_msg_high_latency2_get_climb_rate(msg); + high_latency2->battery = mavlink_msg_high_latency2_get_battery(msg); + high_latency2->custom0 = mavlink_msg_high_latency2_get_custom0(msg); + high_latency2->custom1 = mavlink_msg_high_latency2_get_custom1(msg); + high_latency2->custom2 = mavlink_msg_high_latency2_get_custom2(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY2_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY2_LEN; + memset(high_latency2, 0, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); + memcpy(high_latency2, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/lib/main/MAVLink/common/mavlink_msg_highres_imu.h b/lib/main/MAVLink/common/mavlink_msg_highres_imu.h index be7e5d33d2..59718e30cd 100755 --- a/lib/main/MAVLink/common/mavlink_msg_highres_imu.h +++ b/lib/main/MAVLink/common/mavlink_msg_highres_imu.h @@ -3,24 +3,24 @@ #define MAVLINK_MSG_ID_HIGHRES_IMU 105 -MAVPACKED( + typedef struct __mavlink_highres_imu_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float xacc; /*< X acceleration (m/s^2)*/ - float yacc; /*< Y acceleration (m/s^2)*/ - float zacc; /*< Z acceleration (m/s^2)*/ - float xgyro; /*< Angular speed around X axis (rad / sec)*/ - float ygyro; /*< Angular speed around Y axis (rad / sec)*/ - float zgyro; /*< Angular speed around Z axis (rad / sec)*/ - float xmag; /*< X Magnetic field (Gauss)*/ - float ymag; /*< Y Magnetic field (Gauss)*/ - float zmag; /*< Z Magnetic field (Gauss)*/ - float abs_pressure; /*< Absolute pressure in millibar*/ - float diff_pressure; /*< Differential pressure in millibar*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< Temperature in degrees celsius*/ - uint16_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/ -}) mavlink_highres_imu_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float xacc; /*< [m/s/s] X acceleration*/ + float yacc; /*< [m/s/s] Y acceleration*/ + float zacc; /*< [m/s/s] Z acceleration*/ + float xgyro; /*< [rad/s] Angular speed around X axis*/ + float ygyro; /*< [rad/s] Angular speed around Y axis*/ + float zgyro; /*< [rad/s] Angular speed around Z axis*/ + float xmag; /*< [gauss] X Magnetic field*/ + float ymag; /*< [gauss] Y Magnetic field*/ + float zmag; /*< [gauss] Z Magnetic field*/ + float abs_pressure; /*< [mbar] Absolute pressure*/ + float diff_pressure; /*< [mbar] Differential pressure*/ + float pressure_alt; /*< Altitude calculated from pressure*/ + float temperature; /*< [degC] Temperature*/ + uint16_t fields_updated; /*< Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/ +} mavlink_highres_imu_t; #define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 #define MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN 62 @@ -83,21 +83,21 @@ typedef struct __mavlink_highres_imu_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis + * @param ygyro [rad/s] Angular speed around Y axis + * @param zgyro [rad/s] Angular speed around Z axis + * @param xmag [gauss] X Magnetic field + * @param ymag [gauss] Y Magnetic field + * @param zmag [gauss] Z Magnetic field + * @param abs_pressure [mbar] Absolute pressure + * @param diff_pressure [mbar] Differential pressure + * @param pressure_alt Altitude calculated from pressure + * @param temperature [degC] Temperature + * @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -153,21 +153,21 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis + * @param ygyro [rad/s] Angular speed around Y axis + * @param zgyro [rad/s] Angular speed around Z axis + * @param xmag [gauss] X Magnetic field + * @param ymag [gauss] Y Magnetic field + * @param zmag [gauss] Z Magnetic field + * @param abs_pressure [mbar] Absolute pressure + * @param diff_pressure [mbar] Differential pressure + * @param pressure_alt Altitude calculated from pressure + * @param temperature [degC] Temperature + * @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -249,21 +249,21 @@ static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, ui * @brief Send a highres_imu message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis + * @param ygyro [rad/s] Angular speed around Y axis + * @param zgyro [rad/s] Angular speed around Z axis + * @param xmag [gauss] X Magnetic field + * @param ymag [gauss] Y Magnetic field + * @param zmag [gauss] Z Magnetic field + * @param abs_pressure [mbar] Absolute pressure + * @param diff_pressure [mbar] Differential pressure + * @param pressure_alt Altitude calculated from pressure + * @param temperature [degC] Temperature + * @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -384,7 +384,7 @@ static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field time_usec from highres_imu message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_messa /** * @brief Get field xacc from highres_imu message * - * @return X acceleration (m/s^2) + * @return [m/s/s] X acceleration */ static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* ms /** * @brief Get field yacc from highres_imu message * - * @return Y acceleration (m/s^2) + * @return [m/s/s] Y acceleration */ static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) { @@ -414,7 +414,7 @@ static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* ms /** * @brief Get field zacc from highres_imu message * - * @return Z acceleration (m/s^2) + * @return [m/s/s] Z acceleration */ static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) { @@ -424,7 +424,7 @@ static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* ms /** * @brief Get field xgyro from highres_imu message * - * @return Angular speed around X axis (rad / sec) + * @return [rad/s] Angular speed around X axis */ static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) { @@ -434,7 +434,7 @@ static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* m /** * @brief Get field ygyro from highres_imu message * - * @return Angular speed around Y axis (rad / sec) + * @return [rad/s] Angular speed around Y axis */ static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) { @@ -444,7 +444,7 @@ static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* m /** * @brief Get field zgyro from highres_imu message * - * @return Angular speed around Z axis (rad / sec) + * @return [rad/s] Angular speed around Z axis */ static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) { @@ -454,7 +454,7 @@ static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* m /** * @brief Get field xmag from highres_imu message * - * @return X Magnetic field (Gauss) + * @return [gauss] X Magnetic field */ static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) { @@ -464,7 +464,7 @@ static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* ms /** * @brief Get field ymag from highres_imu message * - * @return Y Magnetic field (Gauss) + * @return [gauss] Y Magnetic field */ static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) { @@ -474,7 +474,7 @@ static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* ms /** * @brief Get field zmag from highres_imu message * - * @return Z Magnetic field (Gauss) + * @return [gauss] Z Magnetic field */ static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) { @@ -484,7 +484,7 @@ static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* ms /** * @brief Get field abs_pressure from highres_imu message * - * @return Absolute pressure in millibar + * @return [mbar] Absolute pressure */ static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) { @@ -494,7 +494,7 @@ static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_messa /** * @brief Get field diff_pressure from highres_imu message * - * @return Differential pressure in millibar + * @return [mbar] Differential pressure */ static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) { @@ -504,7 +504,7 @@ static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_mess /** * @brief Get field pressure_alt from highres_imu message * - * @return Altitude calculated from pressure + * @return Altitude calculated from pressure */ static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) { @@ -514,7 +514,7 @@ static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_messa /** * @brief Get field temperature from highres_imu message * - * @return Temperature in degrees celsius + * @return [degC] Temperature */ static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) { @@ -524,7 +524,7 @@ static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_messag /** * @brief Get field fields_updated from highres_imu message * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature */ static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_actuator_controls.h b/lib/main/MAVLink/common/mavlink_msg_hil_actuator_controls.h index f60e920e5a..31c28db427 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_actuator_controls.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_actuator_controls.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93 -MAVPACKED( + typedef struct __mavlink_hil_actuator_controls_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - uint64_t flags; /*< Flags as bitfield, reserved for future use.*/ - float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/ - uint8_t mode; /*< System mode (MAV_MODE), includes arming state.*/ -}) mavlink_hil_actuator_controls_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint64_t flags; /*< Flags as bitfield, 1: indicate simulation using lockstep.*/ + float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/ + uint8_t mode; /*< System mode. Includes arming state.*/ +} mavlink_hil_actuator_controls_t; #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81 #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81 @@ -27,9 +27,9 @@ typedef struct __mavlink_hil_actuator_controls_t { "HIL_ACTUATOR_CONTROLS", \ 4, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ } \ } #else @@ -37,9 +37,9 @@ typedef struct __mavlink_hil_actuator_controls_t { "HIL_ACTUATOR_CONTROLS", \ 4, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_hil_actuator_controls_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. + * @param mode System mode. Includes arming state. + * @param flags Flags as bitfield, 1: indicate simulation using lockstep. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. + * @param mode System mode. Includes arming state. + * @param flags Flags as bitfield, 1: indicate simulation using lockstep. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t sys * @brief Send a hil_actuator_controls message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. + * @param mode System mode. Includes arming state. + * @param flags Flags as bitfield, 1: indicate simulation using lockstep. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t /** * @brief Get field time_usec from hil_actuator_controls message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mav /** * @brief Get field controls from hil_actuator_controls message * - * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. + * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. */ static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavlink_message_t* msg, float *controls) { @@ -242,7 +242,7 @@ static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavl /** * @brief Get field mode from hil_actuator_controls message * - * @return System mode (MAV_MODE), includes arming state. + * @return System mode. Includes arming state. */ static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t* msg) { @@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_m /** * @brief Get field flags from hil_actuator_controls message * - * @return Flags as bitfield, reserved for future use. + * @return Flags as bitfield, 1: indicate simulation using lockstep. */ static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_controls.h b/lib/main/MAVLink/common/mavlink_msg_hil_controls.h index 39dca7eec9..a3bd993bfb 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_controls.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_controls.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_HIL_CONTROLS 91 -MAVPACKED( + typedef struct __mavlink_hil_controls_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float roll_ailerons; /*< Control output -1 .. 1*/ - float pitch_elevator; /*< Control output -1 .. 1*/ - float yaw_rudder; /*< Control output -1 .. 1*/ - float throttle; /*< Throttle 0 .. 1*/ - float aux1; /*< Aux 1, -1 .. 1*/ - float aux2; /*< Aux 2, -1 .. 1*/ - float aux3; /*< Aux 3, -1 .. 1*/ - float aux4; /*< Aux 4, -1 .. 1*/ - uint8_t mode; /*< System mode (MAV_MODE)*/ - uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ -}) mavlink_hil_controls_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float roll_ailerons; /*< Control output -1 .. 1*/ + float pitch_elevator; /*< Control output -1 .. 1*/ + float yaw_rudder; /*< Control output -1 .. 1*/ + float throttle; /*< Throttle 0 .. 1*/ + float aux1; /*< Aux 1, -1 .. 1*/ + float aux2; /*< Aux 2, -1 .. 1*/ + float aux3; /*< Aux 3, -1 .. 1*/ + float aux4; /*< Aux 4, -1 .. 1*/ + uint8_t mode; /*< System mode.*/ + uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ +} mavlink_hil_controls_t; #define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 #define MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN 42 @@ -71,17 +71,17 @@ typedef struct __mavlink_hil_controls_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode. + * @param nav_mode Navigation mode (MAV_NAV_MODE) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -129,17 +129,17 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode. + * @param nav_mode Navigation mode (MAV_NAV_MODE) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -213,17 +213,17 @@ static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, u * @brief Send a hil_controls message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode. + * @param nav_mode Navigation mode (MAV_NAV_MODE) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -328,7 +328,7 @@ static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field time_usec from hil_controls message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) { @@ -338,7 +338,7 @@ static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_mess /** * @brief Get field roll_ailerons from hil_controls message * - * @return Control output -1 .. 1 + * @return Control output -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) { @@ -348,7 +348,7 @@ static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_mes /** * @brief Get field pitch_elevator from hil_controls message * - * @return Control output -1 .. 1 + * @return Control output -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) { @@ -358,7 +358,7 @@ static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_me /** * @brief Get field yaw_rudder from hil_controls message * - * @return Control output -1 .. 1 + * @return Control output -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) { @@ -368,7 +368,7 @@ static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_messag /** * @brief Get field throttle from hil_controls message * - * @return Throttle 0 .. 1 + * @return Throttle 0 .. 1 */ static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) { @@ -378,7 +378,7 @@ static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_ /** * @brief Get field aux1 from hil_controls message * - * @return Aux 1, -1 .. 1 + * @return Aux 1, -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) { @@ -388,7 +388,7 @@ static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* m /** * @brief Get field aux2 from hil_controls message * - * @return Aux 2, -1 .. 1 + * @return Aux 2, -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) { @@ -398,7 +398,7 @@ static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* m /** * @brief Get field aux3 from hil_controls message * - * @return Aux 3, -1 .. 1 + * @return Aux 3, -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* m /** * @brief Get field aux4 from hil_controls message * - * @return Aux 4, -1 .. 1 + * @return Aux 4, -1 .. 1 */ static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* m /** * @brief Get field mode from hil_controls message * - * @return System mode (MAV_MODE) + * @return System mode. */ static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* /** * @brief Get field nav_mode from hil_controls message * - * @return Navigation mode (MAV_NAV_MODE) + * @return Navigation mode (MAV_NAV_MODE) */ static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_gps.h b/lib/main/MAVLink/common/mavlink_msg_hil_gps.h index 8333269ff4..1d1c2575c8 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_gps.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_gps.h @@ -3,22 +3,22 @@ #define MAVLINK_MSG_ID_HIL_GPS 113 -MAVPACKED( + typedef struct __mavlink_hil_gps_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: 65535*/ - int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/ - int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/ - int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ -}) mavlink_hil_gps_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + int32_t lat; /*< [degE7] Latitude (WGS84)*/ + int32_t lon; /*< [degE7] Longitude (WGS84)*/ + int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/ + uint16_t eph; /*< [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535*/ + uint16_t epv; /*< [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535*/ + uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: 65535*/ + int16_t vn; /*< [cm/s] GPS velocity in north direction in earth-fixed NED frame*/ + int16_t ve; /*< [cm/s] GPS velocity in east direction in earth-fixed NED frame*/ + int16_t vd; /*< [cm/s] GPS velocity in down direction in earth-fixed NED frame*/ + uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ +} mavlink_hil_gps_t; #define MAVLINK_MSG_ID_HIL_GPS_LEN 36 #define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36 @@ -36,6 +36,7 @@ typedef struct __mavlink_hil_gps_t { "HIL_GPS", \ 13, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ @@ -46,7 +47,6 @@ typedef struct __mavlink_hil_gps_t { { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ } \ } @@ -55,6 +55,7 @@ typedef struct __mavlink_hil_gps_t { "HIL_GPS", \ 13, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ @@ -65,7 +66,6 @@ typedef struct __mavlink_hil_gps_t { { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ } \ } @@ -77,19 +77,19 @@ typedef struct __mavlink_hil_gps_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [mm] Altitude (MSL). Positive for up. + * @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535 + * @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535 + * @param vel [cm/s] GPS ground speed. If unknown, set to: 65535 + * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame + * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame + * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -141,19 +141,19 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [mm] Altitude (MSL). Positive for up. + * @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535 + * @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535 + * @param vel [cm/s] GPS ground speed. If unknown, set to: 65535 + * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame + * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame + * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -231,19 +231,19 @@ static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_ * @brief Send a hil_gps message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat [degE7] Latitude (WGS84) + * @param lon [degE7] Longitude (WGS84) + * @param alt [mm] Altitude (MSL). Positive for up. + * @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535 + * @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535 + * @param vel [cm/s] GPS ground speed. If unknown, set to: 65535 + * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame + * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame + * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame + * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -356,7 +356,7 @@ static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavli /** * @brief Get field time_usec from hil_gps message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t /** * @brief Get field fix_type from hil_gps message * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) { @@ -376,7 +376,7 @@ static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* /** * @brief Get field lat from hil_gps message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) /** * @brief Get field lon from hil_gps message * - * @return Longitude (WGS84), in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) /** * @brief Get field alt from hil_gps message * - * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @return [mm] Altitude (MSL). Positive for up. */ static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) { @@ -406,7 +406,7 @@ static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) /** * @brief Get field eph from hil_gps message * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @return [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535 */ static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) { @@ -416,7 +416,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) /** * @brief Get field epv from hil_gps message * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @return [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535 */ static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) { @@ -426,7 +426,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) /** * @brief Get field vel from hil_gps message * - * @return GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @return [cm/s] GPS ground speed. If unknown, set to: 65535 */ static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) /** * @brief Get field vn from hil_gps message * - * @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @return [cm/s] GPS velocity in north direction in earth-fixed NED frame */ static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) /** * @brief Get field ve from hil_gps message * - * @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @return [cm/s] GPS velocity in east direction in earth-fixed NED frame */ static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) /** * @brief Get field vd from hil_gps message * - * @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @return [cm/s] GPS velocity in down direction in earth-fixed NED frame */ static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) /** * @brief Get field cog from hil_gps message * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @return [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535 */ static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) /** * @brief Get field satellites_visible from hil_gps message * - * @return Number of satellites visible. If unknown, set to 255 + * @return Number of satellites visible. If unknown, set to 255 */ static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_optical_flow.h b/lib/main/MAVLink/common/mavlink_msg_hil_optical_flow.h index 9d1cf8e7d7..98c61fd5e5 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_optical_flow.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_optical_flow.h @@ -3,21 +3,21 @@ #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 -MAVPACKED( + typedef struct __mavlink_hil_optical_flow_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< RH rotation around X axis (rad)*/ - float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ - float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ - uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ - float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -}) mavlink_hil_optical_flow_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint32_t integration_time_us; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ + float integrated_x; /*< [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ + float integrated_y; /*< [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ + float integrated_xgyro; /*< [rad] RH rotation around X axis*/ + float integrated_ygyro; /*< [rad] RH rotation around Y axis*/ + float integrated_zgyro; /*< [rad] RH rotation around Z axis*/ + uint32_t time_delta_distance_us; /*< [us] Time since the distance was sampled.*/ + float distance; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/ + int16_t temperature; /*< [cdegC] Temperature*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ +} mavlink_hil_optical_flow_t; #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN 44 @@ -35,17 +35,17 @@ typedef struct __mavlink_hil_optical_flow_t { "HIL_OPTICAL_FLOW", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ } \ } #else @@ -53,17 +53,17 @@ typedef struct __mavlink_hil_optical_flow_t { "HIL_OPTICAL_FLOW", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ } \ } #endif @@ -74,18 +74,18 @@ typedef struct __mavlink_hil_optical_flow_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro [rad] RH rotation around X axis + * @param integrated_ygyro [rad] RH rotation around Y axis + * @param integrated_zgyro [rad] RH rotation around Z axis + * @param temperature [cdegC] Temperature + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us [us] Time since the distance was sampled. + * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -135,18 +135,18 @@ static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro [rad] RH rotation around X axis + * @param integrated_ygyro [rad] RH rotation around Y axis + * @param integrated_zgyro [rad] RH rotation around Z axis + * @param temperature [cdegC] Temperature + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us [us] Time since the distance was sampled. + * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -222,18 +222,18 @@ static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_i * @brief Send a hil_optical_flow message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro [rad] RH rotation around X axis + * @param integrated_ygyro [rad] RH rotation around Y axis + * @param integrated_zgyro [rad] RH rotation around Z axis + * @param temperature [cdegC] Temperature + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us [us] Time since the distance was sampled. + * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -342,7 +342,7 @@ static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgb /** * @brief Get field time_usec from hil_optical_flow message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_ /** * @brief Get field sensor_id from hil_optical_flow message * - * @return Sensor ID + * @return Sensor ID */ static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_m /** * @brief Get field integration_time_us from hil_optical_flow message * - * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. */ static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(cons /** * @brief Get field integrated_x from hil_optical_flow message * - * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @return [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) */ static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg) { @@ -382,7 +382,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_ /** * @brief Get field integrated_y from hil_optical_flow message * - * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @return [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) */ static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg) { @@ -392,7 +392,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_ /** * @brief Get field integrated_xgyro from hil_optical_flow message * - * @return RH rotation around X axis (rad) + * @return [rad] RH rotation around X axis */ static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg) { @@ -402,7 +402,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavl /** * @brief Get field integrated_ygyro from hil_optical_flow message * - * @return RH rotation around Y axis (rad) + * @return [rad] RH rotation around Y axis */ static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg) { @@ -412,7 +412,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavl /** * @brief Get field integrated_zgyro from hil_optical_flow message * - * @return RH rotation around Z axis (rad) + * @return [rad] RH rotation around Z axis */ static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg) { @@ -422,7 +422,7 @@ static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavl /** * @brief Get field temperature from hil_optical_flow message * - * @return Temperature * 100 in centi-degrees Celsius + * @return [cdegC] Temperature */ static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg) { @@ -432,7 +432,7 @@ static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink /** * @brief Get field quality from hil_optical_flow message * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality */ static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) { @@ -442,7 +442,7 @@ static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_mes /** * @brief Get field time_delta_distance_us from hil_optical_flow message * - * @return Time in microseconds since the distance was sampled. + * @return [us] Time since the distance was sampled. */ static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg) { @@ -452,7 +452,7 @@ static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(c /** * @brief Get field distance from hil_optical_flow message * - * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. */ static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_rc_inputs_raw.h b/lib/main/MAVLink/common/mavlink_msg_hil_rc_inputs_raw.h index 04b8a45a44..28ce091ab8 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_rc_inputs_raw.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_rc_inputs_raw.h @@ -3,23 +3,23 @@ #define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 -MAVPACKED( + typedef struct __mavlink_hil_rc_inputs_raw_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds*/ - uint16_t chan9_raw; /*< RC channel 9 value, in microseconds*/ - uint16_t chan10_raw; /*< RC channel 10 value, in microseconds*/ - uint16_t chan11_raw; /*< RC channel 11 value, in microseconds*/ - uint16_t chan12_raw; /*< RC channel 12 value, in microseconds*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 255: 100%*/ -}) mavlink_hil_rc_inputs_raw_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint16_t chan1_raw; /*< [us] RC channel 1 value*/ + uint16_t chan2_raw; /*< [us] RC channel 2 value*/ + uint16_t chan3_raw; /*< [us] RC channel 3 value*/ + uint16_t chan4_raw; /*< [us] RC channel 4 value*/ + uint16_t chan5_raw; /*< [us] RC channel 5 value*/ + uint16_t chan6_raw; /*< [us] RC channel 6 value*/ + uint16_t chan7_raw; /*< [us] RC channel 7 value*/ + uint16_t chan8_raw; /*< [us] RC channel 8 value*/ + uint16_t chan9_raw; /*< [us] RC channel 9 value*/ + uint16_t chan10_raw; /*< [us] RC channel 10 value*/ + uint16_t chan11_raw; /*< [us] RC channel 11 value*/ + uint16_t chan12_raw; /*< [us] RC channel 12 value*/ + uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/ +} mavlink_hil_rc_inputs_raw_t; #define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 #define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN 33 @@ -80,20 +80,20 @@ typedef struct __mavlink_hil_rc_inputs_raw_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param chan1_raw [us] RC channel 1 value + * @param chan2_raw [us] RC channel 2 value + * @param chan3_raw [us] RC channel 3 value + * @param chan4_raw [us] RC channel 4 value + * @param chan5_raw [us] RC channel 5 value + * @param chan6_raw [us] RC channel 6 value + * @param chan7_raw [us] RC channel 7 value + * @param chan8_raw [us] RC channel 8 value + * @param chan9_raw [us] RC channel 9 value + * @param chan10_raw [us] RC channel 10 value + * @param chan11_raw [us] RC channel 11 value + * @param chan12_raw [us] RC channel 12 value + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param chan1_raw [us] RC channel 1 value + * @param chan2_raw [us] RC channel 2 value + * @param chan3_raw [us] RC channel 3 value + * @param chan4_raw [us] RC channel 4 value + * @param chan5_raw [us] RC channel 5 value + * @param chan6_raw [us] RC channel 6 value + * @param chan7_raw [us] RC channel 7 value + * @param chan8_raw [us] RC channel 8 value + * @param chan9_raw [us] RC channel 9 value + * @param chan10_raw [us] RC channel 10 value + * @param chan11_raw [us] RC channel 11 value + * @param chan12_raw [us] RC channel 12 value + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_ * @brief Send a hil_rc_inputs_raw message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param chan1_raw [us] RC channel 1 value + * @param chan2_raw [us] RC channel 2 value + * @param chan3_raw [us] RC channel 3 value + * @param chan4_raw [us] RC channel 4 value + * @param chan5_raw [us] RC channel 5 value + * @param chan6_raw [us] RC channel 6 value + * @param chan7_raw [us] RC channel 7 value + * @param chan8_raw [us] RC channel 8 value + * @param chan9_raw [us] RC channel 9 value + * @param chan10_raw [us] RC channel 10 value + * @param chan11_raw [us] RC channel 11 value + * @param chan12_raw [us] RC channel 12 value + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -370,7 +370,7 @@ static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msg /** * @brief Get field time_usec from hil_rc_inputs_raw message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink /** * @brief Get field chan1_raw from hil_rc_inputs_raw message * - * @return RC channel 1 value, in microseconds + * @return [us] RC channel 1 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) { @@ -390,7 +390,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink /** * @brief Get field chan2_raw from hil_rc_inputs_raw message * - * @return RC channel 2 value, in microseconds + * @return [us] RC channel 2 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) { @@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink /** * @brief Get field chan3_raw from hil_rc_inputs_raw message * - * @return RC channel 3 value, in microseconds + * @return [us] RC channel 3 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) { @@ -410,7 +410,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink /** * @brief Get field chan4_raw from hil_rc_inputs_raw message * - * @return RC channel 4 value, in microseconds + * @return [us] RC channel 4 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink /** * @brief Get field chan5_raw from hil_rc_inputs_raw message * - * @return RC channel 5 value, in microseconds + * @return [us] RC channel 5 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) { @@ -430,7 +430,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink /** * @brief Get field chan6_raw from hil_rc_inputs_raw message * - * @return RC channel 6 value, in microseconds + * @return [us] RC channel 6 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) { @@ -440,7 +440,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink /** * @brief Get field chan7_raw from hil_rc_inputs_raw message * - * @return RC channel 7 value, in microseconds + * @return [us] RC channel 7 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink /** * @brief Get field chan8_raw from hil_rc_inputs_raw message * - * @return RC channel 8 value, in microseconds + * @return [us] RC channel 8 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) { @@ -460,7 +460,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink /** * @brief Get field chan9_raw from hil_rc_inputs_raw message * - * @return RC channel 9 value, in microseconds + * @return [us] RC channel 9 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) { @@ -470,7 +470,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink /** * @brief Get field chan10_raw from hil_rc_inputs_raw message * - * @return RC channel 10 value, in microseconds + * @return [us] RC channel 10 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) { @@ -480,7 +480,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlin /** * @brief Get field chan11_raw from hil_rc_inputs_raw message * - * @return RC channel 11 value, in microseconds + * @return [us] RC channel 11 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) { @@ -490,7 +490,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlin /** * @brief Get field chan12_raw from hil_rc_inputs_raw message * - * @return RC channel 12 value, in microseconds + * @return [us] RC channel 12 value */ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) { @@ -500,7 +500,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlin /** * @brief Get field rssi from hil_rc_inputs_raw message * - * @return Receive signal strength indicator, 0: 0%, 255: 100% + * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_sensor.h b/lib/main/MAVLink/common/mavlink_msg_hil_sensor.h index e7f561da33..e9d03cc70e 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_sensor.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_sensor.h @@ -3,24 +3,24 @@ #define MAVLINK_MSG_ID_HIL_SENSOR 107 -MAVPACKED( + typedef struct __mavlink_hil_sensor_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float xacc; /*< X acceleration (m/s^2)*/ - float yacc; /*< Y acceleration (m/s^2)*/ - float zacc; /*< Z acceleration (m/s^2)*/ - float xgyro; /*< Angular speed around X axis in body frame (rad / sec)*/ - float ygyro; /*< Angular speed around Y axis in body frame (rad / sec)*/ - float zgyro; /*< Angular speed around Z axis in body frame (rad / sec)*/ - float xmag; /*< X Magnetic field (Gauss)*/ - float ymag; /*< Y Magnetic field (Gauss)*/ - float zmag; /*< Z Magnetic field (Gauss)*/ - float abs_pressure; /*< Absolute pressure in millibar*/ - float diff_pressure; /*< Differential pressure (airspeed) in millibar*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< Temperature in degrees celsius*/ - uint32_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/ -}) mavlink_hil_sensor_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float xacc; /*< [m/s/s] X acceleration*/ + float yacc; /*< [m/s/s] Y acceleration*/ + float zacc; /*< [m/s/s] Z acceleration*/ + float xgyro; /*< [rad/s] Angular speed around X axis in body frame*/ + float ygyro; /*< [rad/s] Angular speed around Y axis in body frame*/ + float zgyro; /*< [rad/s] Angular speed around Z axis in body frame*/ + float xmag; /*< [gauss] X Magnetic field*/ + float ymag; /*< [gauss] Y Magnetic field*/ + float zmag; /*< [gauss] Z Magnetic field*/ + float abs_pressure; /*< [mbar] Absolute pressure*/ + float diff_pressure; /*< [mbar] Differential pressure (airspeed)*/ + float pressure_alt; /*< Altitude calculated from pressure*/ + float temperature; /*< [degC] Temperature*/ + uint32_t fields_updated; /*< Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/ +} mavlink_hil_sensor_t; #define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 #define MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN 64 @@ -83,21 +83,21 @@ typedef struct __mavlink_hil_sensor_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis in body frame + * @param ygyro [rad/s] Angular speed around Y axis in body frame + * @param zgyro [rad/s] Angular speed around Z axis in body frame + * @param xmag [gauss] X Magnetic field + * @param ymag [gauss] Y Magnetic field + * @param zmag [gauss] Z Magnetic field + * @param abs_pressure [mbar] Absolute pressure + * @param diff_pressure [mbar] Differential pressure (airspeed) + * @param pressure_alt Altitude calculated from pressure + * @param temperature [degC] Temperature + * @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -153,21 +153,21 @@ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis in body frame + * @param ygyro [rad/s] Angular speed around Y axis in body frame + * @param zgyro [rad/s] Angular speed around Z axis in body frame + * @param xmag [gauss] X Magnetic field + * @param ymag [gauss] Y Magnetic field + * @param zmag [gauss] Z Magnetic field + * @param abs_pressure [mbar] Absolute pressure + * @param diff_pressure [mbar] Differential pressure (airspeed) + * @param pressure_alt Altitude calculated from pressure + * @param temperature [degC] Temperature + * @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -249,21 +249,21 @@ static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uin * @brief Send a hil_sensor message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis in body frame + * @param ygyro [rad/s] Angular speed around Y axis in body frame + * @param zgyro [rad/s] Angular speed around Z axis in body frame + * @param xmag [gauss] X Magnetic field + * @param ymag [gauss] Y Magnetic field + * @param zmag [gauss] Z Magnetic field + * @param abs_pressure [mbar] Absolute pressure + * @param diff_pressure [mbar] Differential pressure (airspeed) + * @param pressure_alt Altitude calculated from pressure + * @param temperature [degC] Temperature + * @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -384,7 +384,7 @@ static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field time_usec from hil_sensor message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_messag /** * @brief Get field xacc from hil_sensor message * - * @return X acceleration (m/s^2) + * @return [m/s/s] X acceleration */ static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg /** * @brief Get field yacc from hil_sensor message * - * @return Y acceleration (m/s^2) + * @return [m/s/s] Y acceleration */ static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg) { @@ -414,7 +414,7 @@ static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg /** * @brief Get field zacc from hil_sensor message * - * @return Z acceleration (m/s^2) + * @return [m/s/s] Z acceleration */ static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg) { @@ -424,7 +424,7 @@ static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg /** * @brief Get field xgyro from hil_sensor message * - * @return Angular speed around X axis in body frame (rad / sec) + * @return [rad/s] Angular speed around X axis in body frame */ static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg) { @@ -434,7 +434,7 @@ static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* ms /** * @brief Get field ygyro from hil_sensor message * - * @return Angular speed around Y axis in body frame (rad / sec) + * @return [rad/s] Angular speed around Y axis in body frame */ static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg) { @@ -444,7 +444,7 @@ static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* ms /** * @brief Get field zgyro from hil_sensor message * - * @return Angular speed around Z axis in body frame (rad / sec) + * @return [rad/s] Angular speed around Z axis in body frame */ static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg) { @@ -454,7 +454,7 @@ static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* ms /** * @brief Get field xmag from hil_sensor message * - * @return X Magnetic field (Gauss) + * @return [gauss] X Magnetic field */ static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg) { @@ -464,7 +464,7 @@ static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg /** * @brief Get field ymag from hil_sensor message * - * @return Y Magnetic field (Gauss) + * @return [gauss] Y Magnetic field */ static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg) { @@ -474,7 +474,7 @@ static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg /** * @brief Get field zmag from hil_sensor message * - * @return Z Magnetic field (Gauss) + * @return [gauss] Z Magnetic field */ static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg) { @@ -484,7 +484,7 @@ static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg /** * @brief Get field abs_pressure from hil_sensor message * - * @return Absolute pressure in millibar + * @return [mbar] Absolute pressure */ static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg) { @@ -494,7 +494,7 @@ static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_messag /** * @brief Get field diff_pressure from hil_sensor message * - * @return Differential pressure (airspeed) in millibar + * @return [mbar] Differential pressure (airspeed) */ static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg) { @@ -504,7 +504,7 @@ static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_messa /** * @brief Get field pressure_alt from hil_sensor message * - * @return Altitude calculated from pressure + * @return Altitude calculated from pressure */ static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg) { @@ -514,7 +514,7 @@ static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_messag /** * @brief Get field temperature from hil_sensor message * - * @return Temperature in degrees celsius + * @return [degC] Temperature */ static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg) { @@ -524,7 +524,7 @@ static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message /** * @brief Get field fields_updated from hil_sensor message * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @return Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. */ static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_state.h b/lib/main/MAVLink/common/mavlink_msg_hil_state.h index 722c5835be..e5c4ed8097 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_state.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_state.h @@ -3,25 +3,25 @@ #define MAVLINK_MSG_ID_HIL_STATE 90 -MAVPACKED( + typedef struct __mavlink_hil_state_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float roll; /*< Roll angle (rad)*/ - float pitch; /*< Pitch angle (rad)*/ - float yaw; /*< Yaw angle (rad)*/ - float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ - float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ - float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ - int32_t lat; /*< Latitude, expressed as * 1E7*/ - int32_t lon; /*< Longitude, expressed as * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ -}) mavlink_hil_state_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float roll; /*< [rad] Roll angle*/ + float pitch; /*< [rad] Pitch angle*/ + float yaw; /*< [rad] Yaw angle*/ + float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/ + float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/ + float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/ + int32_t lat; /*< [degE7] Latitude*/ + int32_t lon; /*< [degE7] Longitude*/ + int32_t alt; /*< [mm] Altitude*/ + int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/ + int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/ + int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/ + int16_t xacc; /*< [mG] X acceleration*/ + int16_t yacc; /*< [mG] Y acceleration*/ + int16_t zacc; /*< [mG] Z acceleration*/ +} mavlink_hil_state_t; #define MAVLINK_MSG_ID_HIL_STATE_LEN 56 #define MAVLINK_MSG_ID_HIL_STATE_MIN_LEN 56 @@ -86,22 +86,22 @@ typedef struct __mavlink_hil_state_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle + * @param rollspeed [rad/s] Body frame roll / phi angular speed + * @param pitchspeed [rad/s] Body frame pitch / theta angular speed + * @param yawspeed [rad/s] Body frame yaw / psi angular speed + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude + * @param vx [cm/s] Ground X Speed (Latitude) + * @param vy [cm/s] Ground Y Speed (Longitude) + * @param vz [cm/s] Ground Z Speed (Altitude) + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -159,22 +159,22 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle + * @param rollspeed [rad/s] Body frame roll / phi angular speed + * @param pitchspeed [rad/s] Body frame pitch / theta angular speed + * @param yawspeed [rad/s] Body frame yaw / psi angular speed + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude + * @param vx [cm/s] Ground X Speed (Latitude) + * @param vy [cm/s] Ground Y Speed (Longitude) + * @param vz [cm/s] Ground Z Speed (Altitude) + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -258,22 +258,22 @@ static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint * @brief Send a hil_state message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle + * @param rollspeed [rad/s] Body frame roll / phi angular speed + * @param pitchspeed [rad/s] Body frame pitch / theta angular speed + * @param yawspeed [rad/s] Body frame yaw / psi angular speed + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude + * @param vx [cm/s] Ground X Speed (Latitude) + * @param vy [cm/s] Ground Y Speed (Longitude) + * @param vz [cm/s] Ground Z Speed (Altitude) + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -398,7 +398,7 @@ static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field time_usec from hil_state message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message /** * @brief Get field roll from hil_state message * - * @return Roll angle (rad) + * @return [rad] Roll angle */ static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) /** * @brief Get field pitch from hil_state message * - * @return Pitch angle (rad) + * @return [rad] Pitch angle */ static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg /** * @brief Get field yaw from hil_state message * - * @return Yaw angle (rad) + * @return [rad] Yaw angle */ static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) { @@ -438,7 +438,7 @@ static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) /** * @brief Get field rollspeed from hil_state message * - * @return Body frame roll / phi angular speed (rad/s) + * @return [rad/s] Body frame roll / phi angular speed */ static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) { @@ -448,7 +448,7 @@ static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* /** * @brief Get field pitchspeed from hil_state message * - * @return Body frame pitch / theta angular speed (rad/s) + * @return [rad/s] Body frame pitch / theta angular speed */ static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) { @@ -458,7 +458,7 @@ static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t /** * @brief Get field yawspeed from hil_state message * - * @return Body frame yaw / psi angular speed (rad/s) + * @return [rad/s] Body frame yaw / psi angular speed */ static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) { @@ -468,7 +468,7 @@ static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* /** * @brief Get field lat from hil_state message * - * @return Latitude, expressed as * 1E7 + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) { @@ -478,7 +478,7 @@ static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg /** * @brief Get field lon from hil_state message * - * @return Longitude, expressed as * 1E7 + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) { @@ -488,7 +488,7 @@ static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg /** * @brief Get field alt from hil_state message * - * @return Altitude in meters, expressed as * 1000 (millimeters) + * @return [mm] Altitude */ static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) { @@ -498,7 +498,7 @@ static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg /** * @brief Get field vx from hil_state message * - * @return Ground X Speed (Latitude), expressed as m/s * 100 + * @return [cm/s] Ground X Speed (Latitude) */ static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) { @@ -508,7 +508,7 @@ static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) /** * @brief Get field vy from hil_state message * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 + * @return [cm/s] Ground Y Speed (Longitude) */ static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) { @@ -518,7 +518,7 @@ static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) /** * @brief Get field vz from hil_state message * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 + * @return [cm/s] Ground Z Speed (Altitude) */ static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) { @@ -528,7 +528,7 @@ static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) /** * @brief Get field xacc from hil_state message * - * @return X acceleration (mg) + * @return [mG] X acceleration */ static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) { @@ -538,7 +538,7 @@ static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* ms /** * @brief Get field yacc from hil_state message * - * @return Y acceleration (mg) + * @return [mG] Y acceleration */ static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) { @@ -548,7 +548,7 @@ static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* ms /** * @brief Get field zacc from hil_state message * - * @return Z acceleration (mg) + * @return [mG] Z acceleration */ static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_hil_state_quaternion.h b/lib/main/MAVLink/common/mavlink_msg_hil_state_quaternion.h index 442d229bea..a605f39feb 100755 --- a/lib/main/MAVLink/common/mavlink_msg_hil_state_quaternion.h +++ b/lib/main/MAVLink/common/mavlink_msg_hil_state_quaternion.h @@ -3,25 +3,25 @@ #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 -MAVPACKED( + typedef struct __mavlink_hil_state_quaternion_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ - float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ - float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ - float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ - int32_t lat; /*< Latitude, expressed as * 1E7*/ - int32_t lon; /*< Longitude, expressed as * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ - uint16_t ind_airspeed; /*< Indicated airspeed, expressed as m/s * 100*/ - uint16_t true_airspeed; /*< True airspeed, expressed as m/s * 100*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ -}) mavlink_hil_state_quaternion_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ + float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/ + float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/ + float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/ + int32_t lat; /*< [degE7] Latitude*/ + int32_t lon; /*< [degE7] Longitude*/ + int32_t alt; /*< [mm] Altitude*/ + int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/ + int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/ + int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/ + uint16_t ind_airspeed; /*< [cm/s] Indicated airspeed*/ + uint16_t true_airspeed; /*< [cm/s] True airspeed*/ + int16_t xacc; /*< [mG] X acceleration*/ + int16_t yacc; /*< [mG] Y acceleration*/ + int16_t zacc; /*< [mG] Z acceleration*/ +} mavlink_hil_state_quaternion_t; #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN 64 @@ -86,22 +86,22 @@ typedef struct __mavlink_hil_state_quaternion_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 - * @param true_airspeed True airspeed, expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed [rad/s] Body frame roll / phi angular speed + * @param pitchspeed [rad/s] Body frame pitch / theta angular speed + * @param yawspeed [rad/s] Body frame yaw / psi angular speed + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude + * @param vx [cm/s] Ground X Speed (Latitude) + * @param vy [cm/s] Ground Y Speed (Longitude) + * @param vz [cm/s] Ground Z Speed (Altitude) + * @param ind_airspeed [cm/s] Indicated airspeed + * @param true_airspeed [cm/s] True airspeed + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -157,22 +157,22 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 - * @param true_airspeed True airspeed, expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed [rad/s] Body frame roll / phi angular speed + * @param pitchspeed [rad/s] Body frame pitch / theta angular speed + * @param yawspeed [rad/s] Body frame yaw / psi angular speed + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude + * @param vx [cm/s] Ground X Speed (Latitude) + * @param vy [cm/s] Ground Y Speed (Longitude) + * @param vz [cm/s] Ground Z Speed (Altitude) + * @param ind_airspeed [cm/s] Indicated airspeed + * @param true_airspeed [cm/s] True airspeed + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -254,22 +254,22 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t syst * @brief Send a hil_state_quaternion message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 - * @param true_airspeed True airspeed, expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed [rad/s] Body frame roll / phi angular speed + * @param pitchspeed [rad/s] Body frame pitch / theta angular speed + * @param yawspeed [rad/s] Body frame yaw / psi angular speed + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param alt [mm] Altitude + * @param vx [cm/s] Ground X Speed (Latitude) + * @param vy [cm/s] Ground Y Speed (Longitude) + * @param vz [cm/s] Ground Z Speed (Altitude) + * @param ind_airspeed [cm/s] Indicated airspeed + * @param true_airspeed [cm/s] True airspeed + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -390,7 +390,7 @@ static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t * /** * @brief Get field time_usec from hil_state_quaternion message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) { @@ -400,7 +400,7 @@ static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavl /** * @brief Get field attitude_quaternion from hil_state_quaternion message * - * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) */ static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) { @@ -410,7 +410,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion( /** * @brief Get field rollspeed from hil_state_quaternion message * - * @return Body frame roll / phi angular speed (rad/s) + * @return [rad/s] Body frame roll / phi angular speed */ static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink /** * @brief Get field pitchspeed from hil_state_quaternion message * - * @return Body frame pitch / theta angular speed (rad/s) + * @return [rad/s] Body frame pitch / theta angular speed */ static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) { @@ -430,7 +430,7 @@ static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlin /** * @brief Get field yawspeed from hil_state_quaternion message * - * @return Body frame yaw / psi angular speed (rad/s) + * @return [rad/s] Body frame yaw / psi angular speed */ static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) { @@ -440,7 +440,7 @@ static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_ /** * @brief Get field lat from hil_state_quaternion message * - * @return Latitude, expressed as * 1E7 + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_mes /** * @brief Get field lon from hil_state_quaternion message * - * @return Longitude, expressed as * 1E7 + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) { @@ -460,7 +460,7 @@ static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_mes /** * @brief Get field alt from hil_state_quaternion message * - * @return Altitude in meters, expressed as * 1000 (millimeters) + * @return [mm] Altitude */ static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) { @@ -470,7 +470,7 @@ static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_mes /** * @brief Get field vx from hil_state_quaternion message * - * @return Ground X Speed (Latitude), expressed as m/s * 100 + * @return [cm/s] Ground X Speed (Latitude) */ static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) { @@ -480,7 +480,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_mess /** * @brief Get field vy from hil_state_quaternion message * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 + * @return [cm/s] Ground Y Speed (Longitude) */ static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) { @@ -490,7 +490,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_mess /** * @brief Get field vz from hil_state_quaternion message * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 + * @return [cm/s] Ground Z Speed (Altitude) */ static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) { @@ -500,7 +500,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_mess /** * @brief Get field ind_airspeed from hil_state_quaternion message * - * @return Indicated airspeed, expressed as m/s * 100 + * @return [cm/s] Indicated airspeed */ static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) { @@ -510,7 +510,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const m /** * @brief Get field true_airspeed from hil_state_quaternion message * - * @return True airspeed, expressed as m/s * 100 + * @return [cm/s] True airspeed */ static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) { @@ -520,7 +520,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const /** * @brief Get field xacc from hil_state_quaternion message * - * @return X acceleration (mg) + * @return [mG] X acceleration */ static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) { @@ -530,7 +530,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_me /** * @brief Get field yacc from hil_state_quaternion message * - * @return Y acceleration (mg) + * @return [mG] Y acceleration */ static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) { @@ -540,7 +540,7 @@ static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_me /** * @brief Get field zacc from hil_state_quaternion message * - * @return Z acceleration (mg) + * @return [mG] Z acceleration */ static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_home_position.h b/lib/main/MAVLink/common/mavlink_msg_home_position.h index d5ac5e5fa6..d275d1d630 100755 --- a/lib/main/MAVLink/common/mavlink_msg_home_position.h +++ b/lib/main/MAVLink/common/mavlink_msg_home_position.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_HOME_POSITION 242 -MAVPACKED( + typedef struct __mavlink_home_position_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - float x; /*< Local X position of this position in the local coordinate frame*/ - float y; /*< Local Y position of this position in the local coordinate frame*/ - float z; /*< Local Z position of this position in the local coordinate frame*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ -}) mavlink_home_position_t; + int32_t latitude; /*< [degE7] Latitude (WGS84)*/ + int32_t longitude; /*< [degE7] Longitude (WGS84)*/ + int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ + float x; /*< [m] Local X position of this position in the local coordinate frame*/ + float y; /*< [m] Local Y position of this position in the local coordinate frame*/ + float z; /*< [m] Local Z position of this position in the local coordinate frame*/ + float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ + float approach_x; /*< [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_y; /*< [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_z; /*< [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ +} mavlink_home_position_t; #define MAVLINK_MSG_ID_HOME_POSITION_LEN 52 #define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52 @@ -68,16 +68,16 @@ typedef struct __mavlink_home_position_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. + * @param x [m] Local X position of this position in the local coordinate frame + * @param y [m] Local Y position of this position in the local coordinate frame + * @param z [m] Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -121,16 +121,16 @@ static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. + * @param x [m] Local X position of this position in the local coordinate frame + * @param y [m] Local Y position of this position in the local coordinate frame + * @param z [m] Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -200,16 +200,16 @@ static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, * @brief Send a home_position message * @param chan MAVLink channel to send the message * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. + * @param x [m] Local X position of this position in the local coordinate frame + * @param y [m] Local Y position of this position in the local coordinate frame + * @param z [m] Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -306,7 +306,7 @@ static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field latitude from home_position message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_messa /** * @brief Get field longitude from home_position message * - * @return Longitude (WGS84, in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_mess /** * @brief Get field altitude from home_position message * - * @return Altitude (AMSL), in meters * 1000 (positive for up) + * @return [mm] Altitude (MSL). Positive for up. */ static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_messa /** * @brief Get field x from home_position message * - * @return Local X position of this position in the local coordinate frame + * @return [m] Local X position of this position in the local coordinate frame */ static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg /** * @brief Get field y from home_position message * - * @return Local Y position of this position in the local coordinate frame + * @return [m] Local Y position of this position in the local coordinate frame */ static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg /** * @brief Get field z from home_position message * - * @return Local Z position of this position in the local coordinate frame + * @return [m] Local Z position of this position in the local coordinate frame */ static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg /** * @brief Get field q from home_position message * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground */ static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q) { @@ -376,7 +376,7 @@ static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* /** * @brief Get field approach_x from home_position message * - * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline float mavlink_msg_home_position_get_approach_x(const mavlink_messa /** * @brief Get field approach_y from home_position message * - * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline float mavlink_msg_home_position_get_approach_y(const mavlink_messa /** * @brief Get field approach_z from home_position message * - * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_landing_target.h b/lib/main/MAVLink/common/mavlink_msg_landing_target.h index c79dc667c4..b591cb3cfe 100755 --- a/lib/main/MAVLink/common/mavlink_msg_landing_target.h +++ b/lib/main/MAVLink/common/mavlink_msg_landing_target.h @@ -3,17 +3,17 @@ #define MAVLINK_MSG_ID_LANDING_TARGET 149 -MAVPACKED( + typedef struct __mavlink_landing_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/ - float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/ - float distance; /*< Distance to the target from the vehicle in meters*/ - float size_x; /*< Size in radians of target along x-axis*/ - float size_y; /*< Size in radians of target along y-axis*/ - uint8_t target_num; /*< The ID of the target if multiple targets are present*/ - uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/ -}) mavlink_landing_target_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float angle_x; /*< [rad] X-axis angular offset of the target from the center of the image*/ + float angle_y; /*< [rad] Y-axis angular offset of the target from the center of the image*/ + float distance; /*< [m] Distance to the target from the vehicle*/ + float size_x; /*< [rad] Size of target along x-axis*/ + float size_y; /*< [rad] Size of target along y-axis*/ + uint8_t target_num; /*< The ID of the target if multiple targets are present*/ + uint8_t frame; /*< Coordinate frame used for following fields.*/ +} mavlink_landing_target_t; #define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30 #define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30 @@ -31,13 +31,13 @@ typedef struct __mavlink_landing_target_t { "LANDING_TARGET", \ 8, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ + { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ } \ } #else @@ -45,13 +45,13 @@ typedef struct __mavlink_landing_target_t { "LANDING_TARGET", \ 8, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ + { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ } \ } #endif @@ -62,14 +62,14 @@ typedef struct __mavlink_landing_target_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param target_num The ID of the target if multiple targets are present + * @param frame Coordinate frame used for following fields. + * @param angle_x [rad] X-axis angular offset of the target from the center of the image + * @param angle_y [rad] Y-axis angular offset of the target from the center of the image + * @param distance [m] Distance to the target from the vehicle + * @param size_x [rad] Size of target along x-axis + * @param size_y [rad] Size of target along y-axis * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param target_num The ID of the target if multiple targets are present + * @param frame Coordinate frame used for following fields. + * @param angle_x [rad] X-axis angular offset of the target from the center of the image + * @param angle_y [rad] Y-axis angular offset of the target from the center of the image + * @param distance [m] Distance to the target from the vehicle + * @param size_x [rad] Size of target along x-axis + * @param size_y [rad] Size of target along y-axis * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, * @brief Send a landing_target message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param target_num The ID of the target if multiple targets are present + * @param frame Coordinate frame used for following fields. + * @param angle_x [rad] X-axis angular offset of the target from the center of the image + * @param angle_y [rad] Y-axis angular offset of the target from the center of the image + * @param distance [m] Distance to the target from the vehicle + * @param size_x [rad] Size of target along x-axis + * @param size_y [rad] Size of target along y-axis */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -286,7 +286,7 @@ static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf /** * @brief Get field time_usec from landing_target message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg) { @@ -296,7 +296,7 @@ static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_me /** * @brief Get field target_num from landing_target message * - * @return The ID of the target if multiple targets are present + * @return The ID of the target if multiple targets are present */ static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg) { @@ -306,7 +306,7 @@ static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_me /** * @brief Get field frame from landing_target message * - * @return MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @return Coordinate frame used for following fields. */ static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message /** * @brief Get field angle_x from landing_target message * - * @return X-axis angular offset (in radians) of the target from the center of the image + * @return [rad] X-axis angular offset of the target from the center of the image */ static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message /** * @brief Get field angle_y from landing_target message * - * @return Y-axis angular offset (in radians) of the target from the center of the image + * @return [rad] Y-axis angular offset of the target from the center of the image */ static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message /** * @brief Get field distance from landing_target message * - * @return Distance to the target from the vehicle in meters + * @return [m] Distance to the target from the vehicle */ static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline float mavlink_msg_landing_target_get_distance(const mavlink_messag /** * @brief Get field size_x from landing_target message * - * @return Size in radians of target along x-axis + * @return [rad] Size of target along x-axis */ static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_ /** * @brief Get field size_y from landing_target message * - * @return Size in radians of target along y-axis + * @return [rad] Size of target along y-axis */ static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_link_node_status.h b/lib/main/MAVLink/common/mavlink_msg_link_node_status.h new file mode 100644 index 0000000000..8da7b71d9e --- /dev/null +++ b/lib/main/MAVLink/common/mavlink_msg_link_node_status.h @@ -0,0 +1,463 @@ +#pragma once +// MESSAGE LINK_NODE_STATUS PACKING + +#define MAVLINK_MSG_ID_LINK_NODE_STATUS 8 + + +typedef struct __mavlink_link_node_status_t { + uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/ + uint32_t tx_rate; /*< [bytes/s] Transmit rate*/ + uint32_t rx_rate; /*< [bytes/s] Receive rate*/ + uint32_t messages_sent; /*< Messages sent*/ + uint32_t messages_received; /*< Messages received (estimated from counting seq)*/ + uint32_t messages_lost; /*< Messages lost (estimated from counting seq)*/ + uint16_t rx_parse_err; /*< [bytes] Number of bytes that could not be parsed correctly.*/ + uint16_t tx_overflows; /*< [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX*/ + uint16_t rx_overflows; /*< [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX*/ + uint8_t tx_buf; /*< [%] Remaining free transmit buffer space*/ + uint8_t rx_buf; /*< [%] Remaining free receive buffer space*/ +} mavlink_link_node_status_t; + +#define MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN 36 +#define MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN 36 +#define MAVLINK_MSG_ID_8_LEN 36 +#define MAVLINK_MSG_ID_8_MIN_LEN 36 + +#define MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC 117 +#define MAVLINK_MSG_ID_8_CRC 117 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \ + 8, \ + "LINK_NODE_STATUS", \ + 11, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \ + { "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \ + { "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \ + { "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \ + { "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \ + { "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \ + { "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \ + { "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \ + { "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \ + { "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \ + { "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \ + "LINK_NODE_STATUS", \ + 11, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \ + { "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \ + { "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \ + { "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \ + { "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \ + { "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \ + { "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \ + { "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \ + { "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \ + { "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \ + { "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \ + } \ +} +#endif + +/** + * @brief Pack a link_node_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timestamp [ms] Timestamp (time since system boot). + * @param tx_buf [%] Remaining free transmit buffer space + * @param rx_buf [%] Remaining free receive buffer space + * @param tx_rate [bytes/s] Transmit rate + * @param rx_rate [bytes/s] Receive rate + * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly. + * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX + * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX + * @param messages_sent Messages sent + * @param messages_received Messages received (estimated from counting seq) + * @param messages_lost Messages lost (estimated from counting seq) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_link_node_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, tx_rate); + _mav_put_uint32_t(buf, 12, rx_rate); + _mav_put_uint32_t(buf, 16, messages_sent); + _mav_put_uint32_t(buf, 20, messages_received); + _mav_put_uint32_t(buf, 24, messages_lost); + _mav_put_uint16_t(buf, 28, rx_parse_err); + _mav_put_uint16_t(buf, 30, tx_overflows); + _mav_put_uint16_t(buf, 32, rx_overflows); + _mav_put_uint8_t(buf, 34, tx_buf); + _mav_put_uint8_t(buf, 35, rx_buf); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); +#else + mavlink_link_node_status_t packet; + packet.timestamp = timestamp; + packet.tx_rate = tx_rate; + packet.rx_rate = rx_rate; + packet.messages_sent = messages_sent; + packet.messages_received = messages_received; + packet.messages_lost = messages_lost; + packet.rx_parse_err = rx_parse_err; + packet.tx_overflows = tx_overflows; + packet.rx_overflows = rx_overflows; + packet.tx_buf = tx_buf; + packet.rx_buf = rx_buf; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +} + +/** + * @brief Pack a link_node_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timestamp [ms] Timestamp (time since system boot). + * @param tx_buf [%] Remaining free transmit buffer space + * @param rx_buf [%] Remaining free receive buffer space + * @param tx_rate [bytes/s] Transmit rate + * @param rx_rate [bytes/s] Receive rate + * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly. + * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX + * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX + * @param messages_sent Messages sent + * @param messages_received Messages received (estimated from counting seq) + * @param messages_lost Messages lost (estimated from counting seq) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_link_node_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t timestamp,uint8_t tx_buf,uint8_t rx_buf,uint32_t tx_rate,uint32_t rx_rate,uint16_t rx_parse_err,uint16_t tx_overflows,uint16_t rx_overflows,uint32_t messages_sent,uint32_t messages_received,uint32_t messages_lost) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, tx_rate); + _mav_put_uint32_t(buf, 12, rx_rate); + _mav_put_uint32_t(buf, 16, messages_sent); + _mav_put_uint32_t(buf, 20, messages_received); + _mav_put_uint32_t(buf, 24, messages_lost); + _mav_put_uint16_t(buf, 28, rx_parse_err); + _mav_put_uint16_t(buf, 30, tx_overflows); + _mav_put_uint16_t(buf, 32, rx_overflows); + _mav_put_uint8_t(buf, 34, tx_buf); + _mav_put_uint8_t(buf, 35, rx_buf); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); +#else + mavlink_link_node_status_t packet; + packet.timestamp = timestamp; + packet.tx_rate = tx_rate; + packet.rx_rate = rx_rate; + packet.messages_sent = messages_sent; + packet.messages_received = messages_received; + packet.messages_lost = messages_lost; + packet.rx_parse_err = rx_parse_err; + packet.tx_overflows = tx_overflows; + packet.rx_overflows = rx_overflows; + packet.tx_buf = tx_buf; + packet.rx_buf = rx_buf; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +} + +/** + * @brief Encode a link_node_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param link_node_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_link_node_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status) +{ + return mavlink_msg_link_node_status_pack(system_id, component_id, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost); +} + +/** + * @brief Encode a link_node_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param link_node_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_link_node_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status) +{ + return mavlink_msg_link_node_status_pack_chan(system_id, component_id, chan, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost); +} + +/** + * @brief Send a link_node_status message + * @param chan MAVLink channel to send the message + * + * @param timestamp [ms] Timestamp (time since system boot). + * @param tx_buf [%] Remaining free transmit buffer space + * @param rx_buf [%] Remaining free receive buffer space + * @param tx_rate [bytes/s] Transmit rate + * @param rx_rate [bytes/s] Receive rate + * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly. + * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX + * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX + * @param messages_sent Messages sent + * @param messages_received Messages received (estimated from counting seq) + * @param messages_lost Messages lost (estimated from counting seq) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_link_node_status_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, tx_rate); + _mav_put_uint32_t(buf, 12, rx_rate); + _mav_put_uint32_t(buf, 16, messages_sent); + _mav_put_uint32_t(buf, 20, messages_received); + _mav_put_uint32_t(buf, 24, messages_lost); + _mav_put_uint16_t(buf, 28, rx_parse_err); + _mav_put_uint16_t(buf, 30, tx_overflows); + _mav_put_uint16_t(buf, 32, rx_overflows); + _mav_put_uint8_t(buf, 34, tx_buf); + _mav_put_uint8_t(buf, 35, rx_buf); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +#else + mavlink_link_node_status_t packet; + packet.timestamp = timestamp; + packet.tx_rate = tx_rate; + packet.rx_rate = rx_rate; + packet.messages_sent = messages_sent; + packet.messages_received = messages_received; + packet.messages_lost = messages_lost; + packet.rx_parse_err = rx_parse_err; + packet.tx_overflows = tx_overflows; + packet.rx_overflows = rx_overflows; + packet.tx_buf = tx_buf; + packet.rx_buf = rx_buf; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +#endif +} + +/** + * @brief Send a link_node_status message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_link_node_status_send_struct(mavlink_channel_t chan, const mavlink_link_node_status_t* link_node_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_link_node_status_send(chan, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)link_node_status, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +#endif +} + +#if MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_link_node_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, tx_rate); + _mav_put_uint32_t(buf, 12, rx_rate); + _mav_put_uint32_t(buf, 16, messages_sent); + _mav_put_uint32_t(buf, 20, messages_received); + _mav_put_uint32_t(buf, 24, messages_lost); + _mav_put_uint16_t(buf, 28, rx_parse_err); + _mav_put_uint16_t(buf, 30, tx_overflows); + _mav_put_uint16_t(buf, 32, rx_overflows); + _mav_put_uint8_t(buf, 34, tx_buf); + _mav_put_uint8_t(buf, 35, rx_buf); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +#else + mavlink_link_node_status_t *packet = (mavlink_link_node_status_t *)msgbuf; + packet->timestamp = timestamp; + packet->tx_rate = tx_rate; + packet->rx_rate = rx_rate; + packet->messages_sent = messages_sent; + packet->messages_received = messages_received; + packet->messages_lost = messages_lost; + packet->rx_parse_err = rx_parse_err; + packet->tx_overflows = tx_overflows; + packet->rx_overflows = rx_overflows; + packet->tx_buf = tx_buf; + packet->rx_buf = rx_buf; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); +#endif +} +#endif + +#endif + +// MESSAGE LINK_NODE_STATUS UNPACKING + + +/** + * @brief Get field timestamp from link_node_status message + * + * @return [ms] Timestamp (time since system boot). + */ +static inline uint64_t mavlink_msg_link_node_status_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field tx_buf from link_node_status message + * + * @return [%] Remaining free transmit buffer space + */ +static inline uint8_t mavlink_msg_link_node_status_get_tx_buf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field rx_buf from link_node_status message + * + * @return [%] Remaining free receive buffer space + */ +static inline uint8_t mavlink_msg_link_node_status_get_rx_buf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field tx_rate from link_node_status message + * + * @return [bytes/s] Transmit rate + */ +static inline uint32_t mavlink_msg_link_node_status_get_tx_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field rx_rate from link_node_status message + * + * @return [bytes/s] Receive rate + */ +static inline uint32_t mavlink_msg_link_node_status_get_rx_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 12); +} + +/** + * @brief Get field rx_parse_err from link_node_status message + * + * @return [bytes] Number of bytes that could not be parsed correctly. + */ +static inline uint16_t mavlink_msg_link_node_status_get_rx_parse_err(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tx_overflows from link_node_status message + * + * @return [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX + */ +static inline uint16_t mavlink_msg_link_node_status_get_tx_overflows(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field rx_overflows from link_node_status message + * + * @return [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX + */ +static inline uint16_t mavlink_msg_link_node_status_get_rx_overflows(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field messages_sent from link_node_status message + * + * @return Messages sent + */ +static inline uint32_t mavlink_msg_link_node_status_get_messages_sent(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 16); +} + +/** + * @brief Get field messages_received from link_node_status message + * + * @return Messages received (estimated from counting seq) + */ +static inline uint32_t mavlink_msg_link_node_status_get_messages_received(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field messages_lost from link_node_status message + * + * @return Messages lost (estimated from counting seq) + */ +static inline uint32_t mavlink_msg_link_node_status_get_messages_lost(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 24); +} + +/** + * @brief Decode a link_node_status message into a struct + * + * @param msg The message to decode + * @param link_node_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_link_node_status_decode(const mavlink_message_t* msg, mavlink_link_node_status_t* link_node_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + link_node_status->timestamp = mavlink_msg_link_node_status_get_timestamp(msg); + link_node_status->tx_rate = mavlink_msg_link_node_status_get_tx_rate(msg); + link_node_status->rx_rate = mavlink_msg_link_node_status_get_rx_rate(msg); + link_node_status->messages_sent = mavlink_msg_link_node_status_get_messages_sent(msg); + link_node_status->messages_received = mavlink_msg_link_node_status_get_messages_received(msg); + link_node_status->messages_lost = mavlink_msg_link_node_status_get_messages_lost(msg); + link_node_status->rx_parse_err = mavlink_msg_link_node_status_get_rx_parse_err(msg); + link_node_status->tx_overflows = mavlink_msg_link_node_status_get_tx_overflows(msg); + link_node_status->rx_overflows = mavlink_msg_link_node_status_get_rx_overflows(msg); + link_node_status->tx_buf = mavlink_msg_link_node_status_get_tx_buf(msg); + link_node_status->rx_buf = mavlink_msg_link_node_status_get_rx_buf(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN; + memset(link_node_status, 0, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); + memcpy(link_node_status, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/lib/main/MAVLink/common/mavlink_msg_local_position_ned.h b/lib/main/MAVLink/common/mavlink_msg_local_position_ned.h index 4634032dab..48c71d90d7 100755 --- a/lib/main/MAVLink/common/mavlink_msg_local_position_ned.h +++ b/lib/main/MAVLink/common/mavlink_msg_local_position_ned.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 -MAVPACKED( + typedef struct __mavlink_local_position_ned_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float vx; /*< X Speed*/ - float vy; /*< Y Speed*/ - float vz; /*< Z Speed*/ -}) mavlink_local_position_ned_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float x; /*< [m] X Position*/ + float y; /*< [m] Y Position*/ + float z; /*< [m] Z Position*/ + float vx; /*< [m/s] X Speed*/ + float vy; /*< [m/s] Y Speed*/ + float vz; /*< [m/s] Z Speed*/ +} mavlink_local_position_ned_t; #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN 28 @@ -59,13 +59,13 @@ typedef struct __mavlink_local_position_ned_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param vx [m/s] X Speed + * @param vy [m/s] Y Speed + * @param vz [m/s] Z Speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, ui * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param vx [m/s] X Speed + * @param vy [m/s] Y Speed + * @param vz [m/s] Z Speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system * @brief Send a local_position_ned message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param vx [m/s] X Speed + * @param vy [m/s] Y Speed + * @param vz [m/s] Z Speed */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *ms /** * @brief Get field time_boot_ms from local_position_ned message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mav /** * @brief Get field x from local_position_ned message * - * @return X Position + * @return [m] X Position */ static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t /** * @brief Get field y from local_position_ned message * - * @return Y Position + * @return [m] Y Position */ static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t /** * @brief Get field z from local_position_ned message * - * @return Z Position + * @return [m] Z Position */ static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t /** * @brief Get field vx from local_position_ned message * - * @return X Speed + * @return [m/s] X Speed */ static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_ /** * @brief Get field vy from local_position_ned message * - * @return Y Speed + * @return [m/s] Y Speed */ static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_ /** * @brief Get field vz from local_position_ned message * - * @return Z Speed + * @return [m/s] Z Speed */ static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_local_position_ned_cov.h b/lib/main/MAVLink/common/mavlink_msg_local_position_ned_cov.h index e697e46ecf..8497c7d0af 100755 --- a/lib/main/MAVLink/common/mavlink_msg_local_position_ned_cov.h +++ b/lib/main/MAVLink/common/mavlink_msg_local_position_ned_cov.h @@ -3,21 +3,21 @@ #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 -MAVPACKED( + typedef struct __mavlink_local_position_ned_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float vx; /*< X Speed (m/s)*/ - float vy; /*< Y Speed (m/s)*/ - float vz; /*< Z Speed (m/s)*/ - float ax; /*< X Acceleration (m/s^2)*/ - float ay; /*< Y Acceleration (m/s^2)*/ - float az; /*< Z Acceleration (m/s^2)*/ - float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -}) mavlink_local_position_ned_cov_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float x; /*< [m] X Position*/ + float y; /*< [m] Y Position*/ + float z; /*< [m] Z Position*/ + float vx; /*< [m/s] X Speed*/ + float vy; /*< [m/s] Y Speed*/ + float vz; /*< [m/s] Z Speed*/ + float ax; /*< [m/s/s] X Acceleration*/ + float ay; /*< [m/s/s] Y Acceleration*/ + float az; /*< [m/s/s] Z Acceleration*/ + float covariance[45]; /*< Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/ + uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ +} mavlink_local_position_ned_cov_t; #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 225 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 225 @@ -35,6 +35,7 @@ typedef struct __mavlink_local_position_ned_cov_t { "LOCAL_POSITION_NED_COV", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ @@ -45,7 +46,6 @@ typedef struct __mavlink_local_position_ned_cov_t { { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ } \ } #else @@ -53,6 +53,7 @@ typedef struct __mavlink_local_position_ned_cov_t { "LOCAL_POSITION_NED_COV", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ @@ -63,7 +64,6 @@ typedef struct __mavlink_local_position_ned_cov_t { { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ } \ } #endif @@ -74,18 +74,18 @@ typedef struct __mavlink_local_position_ned_cov_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param vx [m/s] X Speed + * @param vy [m/s] Y Speed + * @param vz [m/s] Z Speed + * @param ax [m/s/s] X Acceleration + * @param ay [m/s/s] Y Acceleration + * @param az [m/s/s] Z Acceleration + * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -133,18 +133,18 @@ static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param vx [m/s] X Speed + * @param vy [m/s] Y Speed + * @param vz [m/s] Z Speed + * @param ax [m/s/s] X Acceleration + * @param ay [m/s/s] Y Acceleration + * @param az [m/s/s] Z Acceleration + * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -218,18 +218,18 @@ static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t sy * @brief Send a local_position_ned_cov message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param vx [m/s] X Speed + * @param vy [m/s] Y Speed + * @param vz [m/s] Z Speed + * @param ax [m/s/s] X Acceleration + * @param ay [m/s/s] Y Acceleration + * @param az [m/s/s] Z Acceleration + * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -334,7 +334,7 @@ static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t /** * @brief Get field time_usec from local_position_ned_cov message * - * @return Timestamp (microseconds since system boot or since UNIX epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const ma /** * @brief Get field estimator_type from local_position_ned_cov message * - * @return Class id of the estimator this estimate originated from. + * @return Class id of the estimator this estimate originated from. */ static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(cons /** * @brief Get field x from local_position_ned_cov message * - * @return X Position + * @return [m] X Position */ static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_messa /** * @brief Get field y from local_position_ned_cov message * - * @return Y Position + * @return [m] Y Position */ static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_messa /** * @brief Get field z from local_position_ned_cov message * - * @return Z Position + * @return [m] Z Position */ static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_messa /** * @brief Get field vx from local_position_ned_cov message * - * @return X Speed (m/s) + * @return [m/s] X Speed */ static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_mess /** * @brief Get field vy from local_position_ned_cov message * - * @return Y Speed (m/s) + * @return [m/s] Y Speed */ static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_mess /** * @brief Get field vz from local_position_ned_cov message * - * @return Z Speed (m/s) + * @return [m/s] Z Speed */ static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg) { @@ -414,7 +414,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_mess /** * @brief Get field ax from local_position_ned_cov message * - * @return X Acceleration (m/s^2) + * @return [m/s/s] X Acceleration */ static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg) { @@ -424,7 +424,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_mess /** * @brief Get field ay from local_position_ned_cov message * - * @return Y Acceleration (m/s^2) + * @return [m/s/s] Y Acceleration */ static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg) { @@ -434,7 +434,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_mess /** * @brief Get field az from local_position_ned_cov message * - * @return Z Acceleration (m/s^2) + * @return [m/s/s] Z Acceleration */ static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg) { @@ -444,7 +444,7 @@ static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_mess /** * @brief Get field covariance from local_position_ned_cov message * - * @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @return Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. */ static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance) { diff --git a/lib/main/MAVLink/common/mavlink_msg_local_position_ned_system_global_offset.h b/lib/main/MAVLink/common/mavlink_msg_local_position_ned_system_global_offset.h index e87bcaac9d..8ff2ba6526 100755 --- a/lib/main/MAVLink/common/mavlink_msg_local_position_ned_system_global_offset.h +++ b/lib/main/MAVLink/common/mavlink_msg_local_position_ned_system_global_offset.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 -MAVPACKED( + typedef struct __mavlink_local_position_ned_system_global_offset_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float roll; /*< Roll*/ - float pitch; /*< Pitch*/ - float yaw; /*< Yaw*/ -}) mavlink_local_position_ned_system_global_offset_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float x; /*< [m] X Position*/ + float y; /*< [m] Y Position*/ + float z; /*< [m] Z Position*/ + float roll; /*< [rad] Roll*/ + float pitch; /*< [rad] Pitch*/ + float yaw; /*< [rad] Yaw*/ +} mavlink_local_position_ned_system_global_offset_t; #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN 28 @@ -59,13 +59,13 @@ typedef struct __mavlink_local_position_ned_system_global_offset_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param roll [rad] Roll + * @param pitch [rad] Pitch + * @param yaw [rad] Yaw * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack( * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param roll [rad] Roll + * @param pitch [rad] Pitch + * @param yaw [rad] Yaw * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encod * @brief Send a local_position_ned_system_global_offset message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param x [m] X Position + * @param y [m] Y Position + * @param z [m] Z Position + * @param roll [rad] Roll + * @param pitch [rad] Pitch + * @param yaw [rad] Yaw */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf( /** * @brief Get field time_boot_ms from local_position_ned_system_global_offset message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_t /** * @brief Get field x from local_position_ned_system_global_offset message * - * @return X Position + * @return [m] X Position */ static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(co /** * @brief Get field y from local_position_ned_system_global_offset message * - * @return Y Position + * @return [m] Y Position */ static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(co /** * @brief Get field z from local_position_ned_system_global_offset message * - * @return Z Position + * @return [m] Z Position */ static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(co /** * @brief Get field roll from local_position_ned_system_global_offset message * - * @return Roll + * @return [rad] Roll */ static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll /** * @brief Get field pitch from local_position_ned_system_global_offset message * - * @return Pitch + * @return [rad] Pitch */ static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitc /** * @brief Get field yaw from local_position_ned_system_global_offset message * - * @return Yaw + * @return [rad] Yaw */ static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_log_data.h b/lib/main/MAVLink/common/mavlink_msg_log_data.h index f4adf2f096..37cd777770 100755 --- a/lib/main/MAVLink/common/mavlink_msg_log_data.h +++ b/lib/main/MAVLink/common/mavlink_msg_log_data.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_LOG_DATA 120 -MAVPACKED( + typedef struct __mavlink_log_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t count; /*< Number of bytes (zero for end of log)*/ - uint8_t data[90]; /*< log data*/ -}) mavlink_log_data_t; + uint32_t ofs; /*< Offset into the log*/ + uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ + uint8_t count; /*< [bytes] Number of bytes (zero for end of log)*/ + uint8_t data[90]; /*< log data*/ +} mavlink_log_data_t; #define MAVLINK_MSG_ID_LOG_DATA_LEN 97 #define MAVLINK_MSG_ID_LOG_DATA_MIN_LEN 97 @@ -26,8 +26,8 @@ typedef struct __mavlink_log_data_t { 120, \ "LOG_DATA", \ 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ } \ @@ -36,8 +36,8 @@ typedef struct __mavlink_log_data_t { #define MAVLINK_MESSAGE_INFO_LOG_DATA { \ "LOG_DATA", \ 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ } \ @@ -50,10 +50,10 @@ typedef struct __mavlink_log_data_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count [bytes] Number of bytes (zero for end of log) + * @param data log data * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count [bytes] Number of bytes (zero for end of log) + * @param data log data * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8 * @brief Send a log_data message * @param chan MAVLink channel to send the message * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count [bytes] Number of bytes (zero for end of log) + * @param data log data */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field id from log_data message * - * @return Log id (from LOG_ENTRY reply) + * @return Log id (from LOG_ENTRY reply) */ static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) /** * @brief Get field ofs from log_data message * - * @return Offset into the log + * @return Offset into the log */ static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) { @@ -242,7 +242,7 @@ static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg /** * @brief Get field count from log_data message * - * @return Number of bytes (zero for end of log) + * @return [bytes] Number of bytes (zero for end of log) */ static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) { @@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* ms /** * @brief Get field data from log_data message * - * @return log data + * @return log data */ static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) { diff --git a/lib/main/MAVLink/common/mavlink_msg_log_entry.h b/lib/main/MAVLink/common/mavlink_msg_log_entry.h index 733e4e7f9e..3020dc74e6 100755 --- a/lib/main/MAVLink/common/mavlink_msg_log_entry.h +++ b/lib/main/MAVLink/common/mavlink_msg_log_entry.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_LOG_ENTRY 118 -MAVPACKED( + typedef struct __mavlink_log_entry_t { - uint32_t time_utc; /*< UTC timestamp of log in seconds since 1970, or 0 if not available*/ - uint32_t size; /*< Size of the log (may be approximate) in bytes*/ - uint16_t id; /*< Log id*/ - uint16_t num_logs; /*< Total number of logs*/ - uint16_t last_log_num; /*< High log number*/ -}) mavlink_log_entry_t; + uint32_t time_utc; /*< [s] UTC timestamp of log since 1970, or 0 if not available*/ + uint32_t size; /*< [bytes] Size of the log (may be approximate)*/ + uint16_t id; /*< Log id*/ + uint16_t num_logs; /*< Total number of logs*/ + uint16_t last_log_num; /*< High log number*/ +} mavlink_log_entry_t; #define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 #define MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN 14 @@ -27,22 +27,22 @@ typedef struct __mavlink_log_entry_t { 118, \ "LOG_ENTRY", \ 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ + { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ + { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ "LOG_ENTRY", \ 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ + { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ + { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ } \ } #endif @@ -53,11 +53,11 @@ typedef struct __mavlink_log_entry_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available + * @param size [bytes] Size of the log (may be approximate) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -93,11 +93,11 @@ static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available + * @param size [bytes] Size of the log (may be approximate) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -159,11 +159,11 @@ static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint * @brief Send a log_entry message * @param chan MAVLink channel to send the message * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available + * @param size [bytes] Size of the log (may be approximate) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -244,7 +244,7 @@ static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field id from log_entry message * - * @return Log id + * @return Log id */ static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) { @@ -254,7 +254,7 @@ static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg /** * @brief Get field num_logs from log_entry message * - * @return Total number of logs + * @return Total number of logs */ static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) { @@ -264,7 +264,7 @@ static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_ /** * @brief Get field last_log_num from log_entry message * - * @return High log number + * @return High log number */ static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) { @@ -274,7 +274,7 @@ static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_mess /** * @brief Get field time_utc from log_entry message * - * @return UTC timestamp of log in seconds since 1970, or 0 if not available + * @return [s] UTC timestamp of log since 1970, or 0 if not available */ static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) { @@ -284,7 +284,7 @@ static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_ /** * @brief Get field size from log_entry message * - * @return Size of the log (may be approximate) in bytes + * @return [bytes] Size of the log (may be approximate) */ static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_log_erase.h b/lib/main/MAVLink/common/mavlink_msg_log_erase.h index d603771c94..c3e4263e09 100755 --- a/lib/main/MAVLink/common/mavlink_msg_log_erase.h +++ b/lib/main/MAVLink/common/mavlink_msg_log_erase.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_LOG_ERASE 121 -MAVPACKED( + typedef struct __mavlink_log_erase_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_erase_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_erase_t; #define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 #define MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN 2 @@ -44,8 +44,8 @@ typedef struct __mavlink_log_erase_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint * @brief Send a log_erase message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field target_system from log_erase message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_mess /** * @brief Get field target_component from log_erase message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_log_request_data.h b/lib/main/MAVLink/common/mavlink_msg_log_request_data.h index 3fb3d62e49..521b8522cf 100755 --- a/lib/main/MAVLink/common/mavlink_msg_log_request_data.h +++ b/lib/main/MAVLink/common/mavlink_msg_log_request_data.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 -MAVPACKED( + typedef struct __mavlink_log_request_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint32_t count; /*< Number of bytes*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_data_t; + uint32_t ofs; /*< Offset into the log*/ + uint32_t count; /*< [bytes] Number of bytes*/ + uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_data_t; #define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 #define MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN 12 @@ -27,22 +27,22 @@ typedef struct __mavlink_log_request_data_t { 119, \ "LOG_REQUEST_DATA", \ 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ + { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ + { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ "LOG_REQUEST_DATA", \ 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ + { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ + { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ } \ } #endif @@ -53,11 +53,11 @@ typedef struct __mavlink_log_request_data_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count [bytes] Number of bytes * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -93,11 +93,11 @@ static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count [bytes] Number of bytes * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -159,11 +159,11 @@ static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_i * @brief Send a log_request_data message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count [bytes] Number of bytes */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -244,7 +244,7 @@ static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgb /** * @brief Get field target_system from log_request_data message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) { @@ -254,7 +254,7 @@ static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavli /** * @brief Get field target_component from log_request_data message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) { @@ -264,7 +264,7 @@ static inline uint8_t mavlink_msg_log_request_data_get_target_component(const ma /** * @brief Get field id from log_request_data message * - * @return Log id (from LOG_ENTRY reply) + * @return Log id (from LOG_ENTRY reply) */ static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) { @@ -274,7 +274,7 @@ static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message /** * @brief Get field ofs from log_request_data message * - * @return Offset into the log + * @return Offset into the log */ static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) { @@ -284,7 +284,7 @@ static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_messag /** * @brief Get field count from log_request_data message * - * @return Number of bytes + * @return [bytes] Number of bytes */ static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_log_request_end.h b/lib/main/MAVLink/common/mavlink_msg_log_request_end.h index dc0c1e59af..a2a7fe361b 100755 --- a/lib/main/MAVLink/common/mavlink_msg_log_request_end.h +++ b/lib/main/MAVLink/common/mavlink_msg_log_request_end.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_LOG_REQUEST_END 122 -MAVPACKED( + typedef struct __mavlink_log_request_end_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_end_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_end_t; #define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 #define MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN 2 @@ -44,8 +44,8 @@ typedef struct __mavlink_log_request_end_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id * @brief Send a log_request_end message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbu /** * @brief Get field target_system from log_request_end message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlin /** * @brief Get field target_component from log_request_end message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_log_request_list.h b/lib/main/MAVLink/common/mavlink_msg_log_request_list.h index f4b00c9952..4a6dfaa4eb 100755 --- a/lib/main/MAVLink/common/mavlink_msg_log_request_list.h +++ b/lib/main/MAVLink/common/mavlink_msg_log_request_list.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 -MAVPACKED( + typedef struct __mavlink_log_request_list_t { - uint16_t start; /*< First log id (0 for first available)*/ - uint16_t end; /*< Last log id (0xffff for last available)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_list_t; + uint16_t start; /*< First log id (0 for first available)*/ + uint16_t end; /*< Last log id (0xffff for last available)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_list_t; #define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 #define MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN 6 @@ -26,20 +26,20 @@ typedef struct __mavlink_log_request_list_t { 117, \ "LOG_REQUEST_LIST", \ 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ + { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ + { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ "LOG_REQUEST_LIST", \ 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ + { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ + { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_log_request_list_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_i * @brief Send a log_request_list message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgb /** * @brief Get field target_system from log_request_list message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavli /** * @brief Get field target_component from log_request_list message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline uint8_t mavlink_msg_log_request_list_get_target_component(const ma /** * @brief Get field start from log_request_list message * - * @return First log id (0 for first available) + * @return First log id (0 for first available) */ static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_mess /** * @brief Get field end from log_request_list message * - * @return Last log id (0xffff for last available) + * @return Last log id (0xffff for last available) */ static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_manual_control.h b/lib/main/MAVLink/common/mavlink_msg_manual_control.h index 05a25665d4..14e7603a43 100755 --- a/lib/main/MAVLink/common/mavlink_msg_manual_control.h +++ b/lib/main/MAVLink/common/mavlink_msg_manual_control.h @@ -3,15 +3,15 @@ #define MAVLINK_MSG_ID_MANUAL_CONTROL 69 -MAVPACKED( + typedef struct __mavlink_manual_control_t { - int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ - int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ - int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ - int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ - uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ - uint8_t target; /*< The system to be controlled.*/ -}) mavlink_manual_control_t; + int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ + int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ + int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ + int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ + uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ + uint8_t target; /*< The system to be controlled.*/ +} mavlink_manual_control_t; #define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 #define MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN 11 @@ -28,24 +28,24 @@ typedef struct __mavlink_manual_control_t { 69, \ "MANUAL_CONTROL", \ 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ + { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ "MANUAL_CONTROL", \ 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ + { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ } \ } #endif @@ -56,12 +56,12 @@ typedef struct __mavlink_manual_control_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -99,12 +99,12 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -168,12 +168,12 @@ static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, * @brief Send a manual_control message * @param chan MAVLink channel to send the message * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -258,7 +258,7 @@ static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf /** * @brief Get field target from manual_control message * - * @return The system to be controlled. + * @return The system to be controlled. */ static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) { @@ -268,7 +268,7 @@ static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_messag /** * @brief Get field x from manual_control message * - * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. */ static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) { @@ -278,7 +278,7 @@ static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* /** * @brief Get field y from manual_control message * - * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. */ static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) { @@ -288,7 +288,7 @@ static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* /** * @brief Get field z from manual_control message * - * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. */ static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) { @@ -298,7 +298,7 @@ static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* /** * @brief Get field r from manual_control message * - * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. */ static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) { @@ -308,7 +308,7 @@ static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* /** * @brief Get field buttons from manual_control message * - * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. */ static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_manual_setpoint.h b/lib/main/MAVLink/common/mavlink_msg_manual_setpoint.h index 04d50a834a..4bc42b1400 100755 --- a/lib/main/MAVLink/common/mavlink_msg_manual_setpoint.h +++ b/lib/main/MAVLink/common/mavlink_msg_manual_setpoint.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 -MAVPACKED( + typedef struct __mavlink_manual_setpoint_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float roll; /*< Desired roll rate in radians per second*/ - float pitch; /*< Desired pitch rate in radians per second*/ - float yaw; /*< Desired yaw rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1*/ - uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ - uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ -}) mavlink_manual_setpoint_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float roll; /*< [rad/s] Desired roll rate*/ + float pitch; /*< [rad/s] Desired pitch rate*/ + float yaw; /*< [rad/s] Desired yaw rate*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1*/ + uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ + uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ +} mavlink_manual_setpoint_t; #define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 #define MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN 22 @@ -59,13 +59,13 @@ typedef struct __mavlink_manual_setpoint_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param roll [rad/s] Desired roll rate + * @param pitch [rad/s] Desired pitch rate + * @param yaw [rad/s] Desired yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param roll [rad/s] Desired roll rate + * @param pitch [rad/s] Desired pitch rate + * @param yaw [rad/s] Desired yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id * @brief Send a manual_setpoint message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param roll [rad/s] Desired roll rate + * @param pitch [rad/s] Desired pitch rate + * @param yaw [rad/s] Desired yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbu /** * @brief Get field time_boot_ms from manual_setpoint message * - * @return Timestamp in milliseconds since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlin /** * @brief Get field roll from manual_setpoint message * - * @return Desired roll rate in radians per second + * @return [rad/s] Desired roll rate */ static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t /** * @brief Get field pitch from manual_setpoint message * - * @return Desired pitch rate in radians per second + * @return [rad/s] Desired pitch rate */ static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_ /** * @brief Get field yaw from manual_setpoint message * - * @return Desired yaw rate in radians per second + * @return [rad/s] Desired yaw rate */ static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* /** * @brief Get field thrust from manual_setpoint message * - * @return Collective thrust, normalized to 0 .. 1 + * @return Collective thrust, normalized to 0 .. 1 */ static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message /** * @brief Get field mode_switch from manual_setpoint message * - * @return Flight mode switch position, 0.. 255 + * @return Flight mode switch position, 0.. 255 */ static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_ /** * @brief Get field manual_override_switch from manual_setpoint message * - * @return Override mode switch position, 0.. 255 + * @return Override mode switch position, 0.. 255 */ static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_memory_vect.h b/lib/main/MAVLink/common/mavlink_msg_memory_vect.h index efc0e62393..c331547473 100755 --- a/lib/main/MAVLink/common/mavlink_msg_memory_vect.h +++ b/lib/main/MAVLink/common/mavlink_msg_memory_vect.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_MEMORY_VECT 249 -MAVPACKED( + typedef struct __mavlink_memory_vect_t { - uint16_t address; /*< Starting address of the debug variables*/ - uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ - uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ - int8_t value[32]; /*< Memory contents at specified address*/ -}) mavlink_memory_vect_t; + uint16_t address; /*< Starting address of the debug variables*/ + uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ + uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ + int8_t value[32]; /*< Memory contents at specified address*/ +} mavlink_memory_vect_t; #define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 #define MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN 36 @@ -50,10 +50,10 @@ typedef struct __mavlink_memory_vect_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, ui * @brief Send a memory_vect message * @param chan MAVLink channel to send the message * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field address from memory_vect message * - * @return Starting address of the debug variables + * @return Starting address of the debug variables */ static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message /** * @brief Get field ver from memory_vect message * - * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below */ static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) { @@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* m /** * @brief Get field type from memory_vect message * - * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 */ static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) { @@ -252,7 +252,7 @@ static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* /** * @brief Get field value from memory_vect message * - * @return Memory contents at specified address + * @return Memory contents at specified address */ static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) { diff --git a/lib/main/MAVLink/common/mavlink_msg_message_interval.h b/lib/main/MAVLink/common/mavlink_msg_message_interval.h index 95b501ffe5..a6a52b1fdc 100755 --- a/lib/main/MAVLink/common/mavlink_msg_message_interval.h +++ b/lib/main/MAVLink/common/mavlink_msg_message_interval.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244 -MAVPACKED( + typedef struct __mavlink_message_interval_t { - int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ - uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ -}) mavlink_message_interval_t; + int32_t interval_us; /*< [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ + uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ +} mavlink_message_interval_t; #define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6 #define MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN 6 @@ -24,16 +24,16 @@ typedef struct __mavlink_message_interval_t { 244, \ "MESSAGE_INTERVAL", \ 2, \ - { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ + { { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ + { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ "MESSAGE_INTERVAL", \ 2, \ - { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ + { { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ + { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ } \ } #endif @@ -44,8 +44,8 @@ typedef struct __mavlink_message_interval_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_i * @brief Send a message_interval message * @param chan MAVLink channel to send the message * - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgb /** * @brief Get field message_id from message_interval message * - * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. */ static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink /** * @brief Get field interval_us from message_interval message * - * @return The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @return [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. */ static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_ack.h b/lib/main/MAVLink/common/mavlink_msg_mission_ack.h index 9616a0fe84..182825a5ea 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_ack.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_ack.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_MISSION_ACK 47 -MAVPACKED( + typedef struct __mavlink_mission_ack_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type; /*< See MAV_MISSION_RESULT enum*/ -}) mavlink_mission_ack_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t type; /*< Mission result.*/ +} mavlink_mission_ack_t; #define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 #define MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN 3 @@ -47,9 +47,9 @@ typedef struct __mavlink_mission_ack_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum + * @param target_system System ID + * @param target_component Component ID + * @param type Mission result. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum + * @param target_system System ID + * @param target_component Component ID + * @param type Mission result. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, ui * @brief Send a mission_ack message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum + * @param target_system System ID + * @param target_component Component ID + * @param type Mission result. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field target_system from mission_ack message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_me /** * @brief Get field target_component from mission_ack message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink /** * @brief Get field type from mission_ack message * - * @return See MAV_MISSION_RESULT enum + * @return Mission result. */ static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_changed.h b/lib/main/MAVLink/common/mavlink_msg_mission_changed.h new file mode 100644 index 0000000000..28f75098e4 --- /dev/null +++ b/lib/main/MAVLink/common/mavlink_msg_mission_changed.h @@ -0,0 +1,313 @@ +#pragma once +// MESSAGE MISSION_CHANGED PACKING + +#define MAVLINK_MSG_ID_MISSION_CHANGED 52 + + +typedef struct __mavlink_mission_changed_t { + int16_t start_index; /*< Start index for partial mission change (-1 for all items).*/ + int16_t end_index; /*< End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.*/ + uint8_t origin_sysid; /*< System ID of the author of the new mission.*/ + uint8_t origin_compid; /*< Compnent ID of the author of the new mission.*/ + uint8_t mission_type; /*< Mission type.*/ +} mavlink_mission_changed_t; + +#define MAVLINK_MSG_ID_MISSION_CHANGED_LEN 7 +#define MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN 7 +#define MAVLINK_MSG_ID_52_LEN 7 +#define MAVLINK_MSG_ID_52_MIN_LEN 7 + +#define MAVLINK_MSG_ID_MISSION_CHANGED_CRC 132 +#define MAVLINK_MSG_ID_52_CRC 132 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_MISSION_CHANGED { \ + 52, \ + "MISSION_CHANGED", \ + 5, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_changed_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_changed_t, end_index) }, \ + { "origin_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_changed_t, origin_sysid) }, \ + { "origin_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_changed_t, origin_compid) }, \ + { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_changed_t, mission_type) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_MISSION_CHANGED { \ + "MISSION_CHANGED", \ + 5, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_changed_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_changed_t, end_index) }, \ + { "origin_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_changed_t, origin_sysid) }, \ + { "origin_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_changed_t, origin_compid) }, \ + { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_changed_t, mission_type) }, \ + } \ +} +#endif + +/** + * @brief Pack a mission_changed message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param start_index Start index for partial mission change (-1 for all items). + * @param end_index End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1. + * @param origin_sysid System ID of the author of the new mission. + * @param origin_compid Compnent ID of the author of the new mission. + * @param mission_type Mission type. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_changed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int16_t start_index, int16_t end_index, uint8_t origin_sysid, uint8_t origin_compid, uint8_t mission_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CHANGED_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, origin_sysid); + _mav_put_uint8_t(buf, 5, origin_compid); + _mav_put_uint8_t(buf, 6, mission_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CHANGED_LEN); +#else + mavlink_mission_changed_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.origin_sysid = origin_sysid; + packet.origin_compid = origin_compid; + packet.mission_type = mission_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CHANGED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CHANGED; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +} + +/** + * @brief Pack a mission_changed message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param start_index Start index for partial mission change (-1 for all items). + * @param end_index End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1. + * @param origin_sysid System ID of the author of the new mission. + * @param origin_compid Compnent ID of the author of the new mission. + * @param mission_type Mission type. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_changed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int16_t start_index,int16_t end_index,uint8_t origin_sysid,uint8_t origin_compid,uint8_t mission_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CHANGED_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, origin_sysid); + _mav_put_uint8_t(buf, 5, origin_compid); + _mav_put_uint8_t(buf, 6, mission_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CHANGED_LEN); +#else + mavlink_mission_changed_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.origin_sysid = origin_sysid; + packet.origin_compid = origin_compid; + packet.mission_type = mission_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CHANGED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CHANGED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +} + +/** + * @brief Encode a mission_changed struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_changed C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_changed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_changed_t* mission_changed) +{ + return mavlink_msg_mission_changed_pack(system_id, component_id, msg, mission_changed->start_index, mission_changed->end_index, mission_changed->origin_sysid, mission_changed->origin_compid, mission_changed->mission_type); +} + +/** + * @brief Encode a mission_changed struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_changed C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_changed_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_changed_t* mission_changed) +{ + return mavlink_msg_mission_changed_pack_chan(system_id, component_id, chan, msg, mission_changed->start_index, mission_changed->end_index, mission_changed->origin_sysid, mission_changed->origin_compid, mission_changed->mission_type); +} + +/** + * @brief Send a mission_changed message + * @param chan MAVLink channel to send the message + * + * @param start_index Start index for partial mission change (-1 for all items). + * @param end_index End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1. + * @param origin_sysid System ID of the author of the new mission. + * @param origin_compid Compnent ID of the author of the new mission. + * @param mission_type Mission type. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_changed_send(mavlink_channel_t chan, int16_t start_index, int16_t end_index, uint8_t origin_sysid, uint8_t origin_compid, uint8_t mission_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CHANGED_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, origin_sysid); + _mav_put_uint8_t(buf, 5, origin_compid); + _mav_put_uint8_t(buf, 6, mission_type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, buf, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +#else + mavlink_mission_changed_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.origin_sysid = origin_sysid; + packet.origin_compid = origin_compid; + packet.mission_type = mission_type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +#endif +} + +/** + * @brief Send a mission_changed message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_mission_changed_send_struct(mavlink_channel_t chan, const mavlink_mission_changed_t* mission_changed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_mission_changed_send(chan, mission_changed->start_index, mission_changed->end_index, mission_changed->origin_sysid, mission_changed->origin_compid, mission_changed->mission_type); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, (const char *)mission_changed, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +#endif +} + +#if MAVLINK_MSG_ID_MISSION_CHANGED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_changed_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t start_index, int16_t end_index, uint8_t origin_sysid, uint8_t origin_compid, uint8_t mission_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, origin_sysid); + _mav_put_uint8_t(buf, 5, origin_compid); + _mav_put_uint8_t(buf, 6, mission_type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, buf, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +#else + mavlink_mission_changed_t *packet = (mavlink_mission_changed_t *)msgbuf; + packet->start_index = start_index; + packet->end_index = end_index; + packet->origin_sysid = origin_sysid; + packet->origin_compid = origin_compid; + packet->mission_type = mission_type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CHANGED, (const char *)packet, MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_LEN, MAVLINK_MSG_ID_MISSION_CHANGED_CRC); +#endif +} +#endif + +#endif + +// MESSAGE MISSION_CHANGED UNPACKING + + +/** + * @brief Get field start_index from mission_changed message + * + * @return Start index for partial mission change (-1 for all items). + */ +static inline int16_t mavlink_msg_mission_changed_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_changed message + * + * @return End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1. + */ +static inline int16_t mavlink_msg_mission_changed_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Get field origin_sysid from mission_changed message + * + * @return System ID of the author of the new mission. + */ +static inline uint8_t mavlink_msg_mission_changed_get_origin_sysid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field origin_compid from mission_changed message + * + * @return Compnent ID of the author of the new mission. + */ +static inline uint8_t mavlink_msg_mission_changed_get_origin_compid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field mission_type from mission_changed message + * + * @return Mission type. + */ +static inline uint8_t mavlink_msg_mission_changed_get_mission_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Decode a mission_changed message into a struct + * + * @param msg The message to decode + * @param mission_changed C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_changed_decode(const mavlink_message_t* msg, mavlink_mission_changed_t* mission_changed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mission_changed->start_index = mavlink_msg_mission_changed_get_start_index(msg); + mission_changed->end_index = mavlink_msg_mission_changed_get_end_index(msg); + mission_changed->origin_sysid = mavlink_msg_mission_changed_get_origin_sysid(msg); + mission_changed->origin_compid = mavlink_msg_mission_changed_get_origin_compid(msg); + mission_changed->mission_type = mavlink_msg_mission_changed_get_mission_type(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CHANGED_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CHANGED_LEN; + memset(mission_changed, 0, MAVLINK_MSG_ID_MISSION_CHANGED_LEN); + memcpy(mission_changed, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_clear_all.h b/lib/main/MAVLink/common/mavlink_msg_mission_clear_all.h index fa7e20e43c..bfed2d3fc2 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_clear_all.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_clear_all.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 -MAVPACKED( + typedef struct __mavlink_mission_clear_all_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_clear_all_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_clear_all_t; #define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 #define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN 2 @@ -44,8 +44,8 @@ typedef struct __mavlink_mission_clear_all_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_ * @brief Send a mission_clear_all message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msg /** * @brief Get field target_system from mission_clear_all message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavl /** * @brief Get field target_component from mission_clear_all message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_count.h b/lib/main/MAVLink/common/mavlink_msg_mission_count.h index 6ba66ff6f4..8c0cd1c6d0 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_count.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_count.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_MISSION_COUNT 44 -MAVPACKED( + typedef struct __mavlink_mission_count_t { - uint16_t count; /*< Number of mission items in the sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_count_t; + uint16_t count; /*< Number of mission items in the sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_count_t; #define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 #define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4 @@ -25,18 +25,18 @@ typedef struct __mavlink_mission_count_t { 44, \ "MISSION_COUNT", \ 3, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ + { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ "MISSION_COUNT", \ 3, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ + { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_mission_count_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, * @brief Send a mission_count message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field target_system from mission_count message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_ /** * @brief Get field target_component from mission_count message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavli /** * @brief Get field count from mission_count message * - * @return Number of mission items in the sequence + * @return Number of mission items in the sequence */ static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_current.h b/lib/main/MAVLink/common/mavlink_msg_mission_current.h index 802632d34d..13f0fb62bc 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_current.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_current.h @@ -3,10 +3,10 @@ #define MAVLINK_MSG_ID_MISSION_CURRENT 42 -MAVPACKED( + typedef struct __mavlink_mission_current_t { - uint16_t seq; /*< Sequence*/ -}) mavlink_mission_current_t; + uint16_t seq; /*< Sequence*/ +} mavlink_mission_current_t; #define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 #define MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN 2 @@ -41,7 +41,7 @@ typedef struct __mavlink_mission_current_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param seq Sequence + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param seq Sequence + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -123,7 +123,7 @@ static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id * @brief Send a mission_current message * @param chan MAVLink channel to send the message * - * @param seq Sequence + * @param seq Sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -188,7 +188,7 @@ static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbu /** * @brief Get field seq from mission_current message * - * @return Sequence + * @return Sequence */ static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_item.h b/lib/main/MAVLink/common/mavlink_msg_mission_item.h index afcf519d41..0a50b542a5 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_item.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_item.h @@ -3,23 +3,23 @@ #define MAVLINK_MSG_ID_MISSION_ITEM 39 -MAVPACKED( + typedef struct __mavlink_mission_item_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - float x; /*< PARAM5 / local: x position, global: latitude*/ - float y; /*< PARAM6 / y position: global: longitude*/ - float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Sequence*/ - uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_mission_item_t; + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + float x; /*< PARAM5 / local: X coordinate, global: latitude*/ + float y; /*< PARAM6 / local: Y coordinate, global: longitude*/ + float z; /*< PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).*/ + uint16_t seq; /*< Sequence*/ + uint16_t command; /*< The scheduled action for the waypoint.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the waypoint.*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< Autocontinue to next waypoint*/ +} mavlink_mission_item_t; #define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 #define MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN 37 @@ -36,40 +36,40 @@ typedef struct __mavlink_mission_item_t { 39, \ "MISSION_ITEM", \ 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ "MISSION_ITEM", \ 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ } \ } #endif @@ -80,20 +80,20 @@ typedef struct __mavlink_mission_item_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. + * @param command The scheduled action for the waypoint. + * @param current false:0, true:1 + * @param autocontinue Autocontinue to next waypoint + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: X coordinate, global: latitude + * @param y PARAM6 / local: Y coordinate, global: longitude + * @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. + * @param command The scheduled action for the waypoint. + * @param current false:0, true:1 + * @param autocontinue Autocontinue to next waypoint + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: X coordinate, global: latitude + * @param y PARAM6 / local: Y coordinate, global: longitude + * @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, u * @brief Send a mission_item message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. + * @param command The scheduled action for the waypoint. + * @param current false:0, true:1 + * @param autocontinue Autocontinue to next waypoint + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: X coordinate, global: latitude + * @param y PARAM6 / local: Y coordinate, global: longitude + * @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -370,7 +370,7 @@ static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field target_system from mission_item message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_m /** * @brief Get field target_component from mission_item message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) { @@ -390,7 +390,7 @@ static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlin /** * @brief Get field seq from mission_item message * - * @return Sequence + * @return Sequence */ static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) { @@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* /** * @brief Get field frame from mission_item message * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @return The coordinate system of the waypoint. */ static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) { @@ -410,7 +410,7 @@ static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t /** * @brief Get field command from mission_item message * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @return The scheduled action for the waypoint. */ static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_messag /** * @brief Get field current from mission_item message * - * @return false:0, true:1 + * @return false:0, true:1 */ static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) { @@ -430,7 +430,7 @@ static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message /** * @brief Get field autocontinue from mission_item message * - * @return autocontinue to next wp + * @return Autocontinue to next waypoint */ static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) { @@ -440,7 +440,7 @@ static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_me /** * @brief Get field param1 from mission_item message * - * @return PARAM1, see MAV_CMD enum + * @return PARAM1, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* /** * @brief Get field param2 from mission_item message * - * @return PARAM2, see MAV_CMD enum + * @return PARAM2, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) { @@ -460,7 +460,7 @@ static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* /** * @brief Get field param3 from mission_item message * - * @return PARAM3, see MAV_CMD enum + * @return PARAM3, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) { @@ -470,7 +470,7 @@ static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* /** * @brief Get field param4 from mission_item message * - * @return PARAM4, see MAV_CMD enum + * @return PARAM4, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) { @@ -480,7 +480,7 @@ static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* /** * @brief Get field x from mission_item message * - * @return PARAM5 / local: x position, global: latitude + * @return PARAM5 / local: X coordinate, global: latitude */ static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) { @@ -490,7 +490,7 @@ static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) /** * @brief Get field y from mission_item message * - * @return PARAM6 / y position: global: longitude + * @return PARAM6 / local: Y coordinate, global: longitude */ static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) { @@ -500,7 +500,7 @@ static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) /** * @brief Get field z from mission_item message * - * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @return PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). */ static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_item_int.h b/lib/main/MAVLink/common/mavlink_msg_mission_item_int.h index 66847236f2..64572671c9 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_item_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_item_int.h @@ -3,23 +3,23 @@ #define MAVLINK_MSG_ID_MISSION_ITEM_INT 73 -MAVPACKED( + typedef struct __mavlink_mission_item_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ - uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_mission_item_int_t; + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ + int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ + float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ + uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ + uint16_t command; /*< The scheduled action for the waypoint.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the waypoint.*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< Autocontinue to next waypoint*/ +} mavlink_mission_item_int_t; #define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37 #define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37 @@ -36,40 +36,40 @@ typedef struct __mavlink_mission_item_int_t { 73, \ "MISSION_ITEM_INT", \ 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ "MISSION_ITEM_INT", \ 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ } \ } #endif @@ -80,20 +80,20 @@ typedef struct __mavlink_mission_item_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the waypoint. + * @param command The scheduled action for the waypoint. + * @param current false:0, true:1 + * @param autocontinue Autocontinue to next waypoint + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the waypoint. + * @param command The scheduled action for the waypoint. + * @param current false:0, true:1 + * @param autocontinue Autocontinue to next waypoint + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_i * @brief Send a mission_item_int message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the waypoint. + * @param command The scheduled action for the waypoint. + * @param current false:0, true:1 + * @param autocontinue Autocontinue to next waypoint + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -370,7 +370,7 @@ static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgb /** * @brief Get field target_system from mission_item_int message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavli /** * @brief Get field target_component from mission_item_int message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg) { @@ -390,7 +390,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const ma /** * @brief Get field seq from mission_item_int message * - * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). */ static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg) { @@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_messag /** * @brief Get field frame from mission_item_int message * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @return The coordinate system of the waypoint. */ static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg) { @@ -410,7 +410,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_messa /** * @brief Get field command from mission_item_int message * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @return The scheduled action for the waypoint. */ static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_me /** * @brief Get field current from mission_item_int message * - * @return false:0, true:1 + * @return false:0, true:1 */ static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg) { @@ -430,7 +430,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_mes /** * @brief Get field autocontinue from mission_item_int message * - * @return autocontinue to next wp + * @return Autocontinue to next waypoint */ static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg) { @@ -440,7 +440,7 @@ static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlin /** * @brief Get field param1 from mission_item_int message * - * @return PARAM1, see MAV_CMD enum + * @return PARAM1, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_messag /** * @brief Get field param2 from mission_item_int message * - * @return PARAM2, see MAV_CMD enum + * @return PARAM2, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg) { @@ -460,7 +460,7 @@ static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_messag /** * @brief Get field param3 from mission_item_int message * - * @return PARAM3, see MAV_CMD enum + * @return PARAM3, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg) { @@ -470,7 +470,7 @@ static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_messag /** * @brief Get field param4 from mission_item_int message * - * @return PARAM4, see MAV_CMD enum + * @return PARAM4, see MAV_CMD enum */ static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg) { @@ -480,7 +480,7 @@ static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_messag /** * @brief Get field x from mission_item_int message * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 */ static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg) { @@ -490,7 +490,7 @@ static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t /** * @brief Get field y from mission_item_int message * - * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 */ static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg) { @@ -500,7 +500,7 @@ static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t /** * @brief Get field z from mission_item_int message * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. */ static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_item_reached.h b/lib/main/MAVLink/common/mavlink_msg_mission_item_reached.h index 1ad0e29cef..647176b9cd 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_item_reached.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_item_reached.h @@ -3,10 +3,10 @@ #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 -MAVPACKED( + typedef struct __mavlink_mission_item_reached_t { - uint16_t seq; /*< Sequence*/ -}) mavlink_mission_item_reached_t; + uint16_t seq; /*< Sequence*/ +} mavlink_mission_item_reached_t; #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN 2 @@ -41,7 +41,7 @@ typedef struct __mavlink_mission_item_reached_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param seq Sequence + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param seq Sequence + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -123,7 +123,7 @@ static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t syst * @brief Send a mission_item_reached message * @param chan MAVLink channel to send the message * - * @param seq Sequence + * @param seq Sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -188,7 +188,7 @@ static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t * /** * @brief Get field seq from mission_item_reached message * - * @return Sequence + * @return Sequence */ static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_request.h b/lib/main/MAVLink/common/mavlink_msg_mission_request.h index 9d6d48ec34..e3b33cc3ec 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_request.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_request.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_MISSION_REQUEST 40 -MAVPACKED( + typedef struct __mavlink_mission_request_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_t; + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_t; #define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 #define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4 @@ -25,18 +25,18 @@ typedef struct __mavlink_mission_request_t { 40, \ "MISSION_REQUEST", \ 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ "MISSION_REQUEST", \ 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_mission_request_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id * @brief Send a mission_request message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbu /** * @brief Get field target_system from mission_request message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlin /** * @brief Get field target_component from mission_request message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_mission_request_get_target_component(const mav /** * @brief Get field seq from mission_request message * - * @return Sequence + * @return Sequence */ static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_request_int.h b/lib/main/MAVLink/common/mavlink_msg_mission_request_int.h index 3257f94c07..a6c2df9119 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_request_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_request_int.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 -MAVPACKED( + typedef struct __mavlink_mission_request_int_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_int_t; + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_int_t; #define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 4 #define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4 @@ -25,18 +25,18 @@ typedef struct __mavlink_mission_request_int_t { 51, \ "MISSION_REQUEST_INT", \ 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ "MISSION_REQUEST_INT", \ 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_mission_request_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t syste * @brief Send a mission_request_int message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *m /** * @brief Get field target_system from mission_request_int message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const ma /** * @brief Get field target_component from mission_request_int message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const /** * @brief Get field seq from mission_request_int message * - * @return Sequence + * @return Sequence */ static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_request_list.h b/lib/main/MAVLink/common/mavlink_msg_mission_request_list.h index 64c211ba62..8b6659fde7 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_request_list.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_request_list.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 -MAVPACKED( + typedef struct __mavlink_mission_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_list_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_list_t; #define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 #define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN 2 @@ -44,8 +44,8 @@ typedef struct __mavlink_mission_request_list_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t syst * @brief Send a mission_request_list message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t * /** * @brief Get field target_system from mission_request_list message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const m /** * @brief Get field target_component from mission_request_list message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_request_partial_list.h b/lib/main/MAVLink/common/mavlink_msg_mission_request_partial_list.h index aa7576321a..0eda74772e 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_request_partial_list.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_request_partial_list.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 -MAVPACKED( + typedef struct __mavlink_mission_request_partial_list_t { - int16_t start_index; /*< Start index, 0 by default*/ - int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_partial_list_t; + int16_t start_index; /*< Start index*/ + int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_partial_list_t; #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN 6 @@ -26,20 +26,20 @@ typedef struct __mavlink_mission_request_partial_list_t { 37, \ "MISSION_REQUEST_PARTIAL_LIST", \ 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ + { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ "MISSION_REQUEST_PARTIAL_LIST", \ 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ + { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_mission_request_partial_list_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint * @brief Send a mission_request_partial_list message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_mes /** * @brief Get field target_system from mission_request_partial_list message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system /** * @brief Get field target_component from mission_request_partial_list message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_compon /** * @brief Get field start_index from mission_request_partial_list message * - * @return Start index, 0 by default + * @return Start index */ static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(c /** * @brief Get field end_index from mission_request_partial_list message * - * @return End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return End index, -1 by default (-1: send list to end). Else a valid index of the list */ static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_set_current.h b/lib/main/MAVLink/common/mavlink_msg_mission_set_current.h index 50942fc443..41eeba3f58 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_set_current.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_set_current.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 -MAVPACKED( + typedef struct __mavlink_mission_set_current_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_set_current_t; + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_set_current_t; #define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 #define MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN 4 @@ -25,18 +25,18 @@ typedef struct __mavlink_mission_set_current_t { 41, \ "MISSION_SET_CURRENT", \ 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ "MISSION_SET_CURRENT", \ 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_mission_set_current_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t syste * @brief Send a mission_set_current message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *m /** * @brief Get field target_system from mission_set_current message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const ma /** * @brief Get field target_component from mission_set_current message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const /** * @brief Get field seq from mission_set_current message * - * @return Sequence + * @return Sequence */ static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_mission_write_partial_list.h b/lib/main/MAVLink/common/mavlink_msg_mission_write_partial_list.h index 756941b408..c1ede1b215 100755 --- a/lib/main/MAVLink/common/mavlink_msg_mission_write_partial_list.h +++ b/lib/main/MAVLink/common/mavlink_msg_mission_write_partial_list.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 -MAVPACKED( + typedef struct __mavlink_mission_write_partial_list_t { - int16_t start_index; /*< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.*/ - int16_t end_index; /*< End index, equal or greater than start index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_write_partial_list_t; + int16_t start_index; /*< Start index. Must be smaller / equal to the largest index of the current onboard list.*/ + int16_t end_index; /*< End index, equal or greater than start index.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_write_partial_list_t; #define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 #define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN 6 @@ -26,20 +26,20 @@ typedef struct __mavlink_mission_write_partial_list_t { 38, \ "MISSION_WRITE_PARTIAL_LIST", \ 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ + { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ "MISSION_WRITE_PARTIAL_LIST", \ 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ + { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_mission_write_partial_list_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_ * @brief Send a mission_write_partial_list message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_messa /** * @brief Get field target_system from mission_write_partial_list message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(c /** * @brief Get field target_component from mission_write_partial_list message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_componen /** * @brief Get field start_index from mission_write_partial_list message * - * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @return Start index. Must be smaller / equal to the largest index of the current onboard list. */ static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(con /** * @brief Get field end_index from mission_write_partial_list message * - * @return End index, equal or greater than start index. + * @return End index, equal or greater than start index. */ static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_named_value_float.h b/lib/main/MAVLink/common/mavlink_msg_named_value_float.h index 99cf094940..ac3e8382ff 100755 --- a/lib/main/MAVLink/common/mavlink_msg_named_value_float.h +++ b/lib/main/MAVLink/common/mavlink_msg_named_value_float.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 -MAVPACKED( + typedef struct __mavlink_named_value_float_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float value; /*< Floating point value*/ - char name[10]; /*< Name of the debug variable*/ -}) mavlink_named_value_float_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float value; /*< Floating point value*/ + char name[10]; /*< Name of the debug variable*/ +} mavlink_named_value_float_t; #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN 18 @@ -26,8 +26,8 @@ typedef struct __mavlink_named_value_float_t { "NAMED_VALUE_FLOAT", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ } \ } #else @@ -35,8 +35,8 @@ typedef struct __mavlink_named_value_float_t { "NAMED_VALUE_FLOAT", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_named_value_float_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param name Name of the debug variable + * @param value Floating point value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -79,9 +79,9 @@ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param name Name of the debug variable + * @param value Floating point value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -137,9 +137,9 @@ static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_ * @brief Send a named_value_float message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param name Name of the debug variable + * @param value Floating point value */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -208,7 +208,7 @@ static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msg /** * @brief Get field time_boot_ms from named_value_float message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) { @@ -218,7 +218,7 @@ static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavl /** * @brief Get field name from named_value_float message * - * @return Name of the debug variable + * @return Name of the debug variable */ static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) { @@ -228,7 +228,7 @@ static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_mess /** * @brief Get field value from named_value_float message * - * @return Floating point value + * @return Floating point value */ static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_named_value_int.h b/lib/main/MAVLink/common/mavlink_msg_named_value_int.h index b0b3b96603..32dbdc91ce 100755 --- a/lib/main/MAVLink/common/mavlink_msg_named_value_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_named_value_int.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 -MAVPACKED( + typedef struct __mavlink_named_value_int_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t value; /*< Signed integer value*/ - char name[10]; /*< Name of the debug variable*/ -}) mavlink_named_value_int_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + int32_t value; /*< Signed integer value*/ + char name[10]; /*< Name of the debug variable*/ +} mavlink_named_value_int_t; #define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 #define MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN 18 @@ -26,8 +26,8 @@ typedef struct __mavlink_named_value_int_t { "NAMED_VALUE_INT", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ } \ } #else @@ -35,8 +35,8 @@ typedef struct __mavlink_named_value_int_t { "NAMED_VALUE_INT", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_named_value_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param name Name of the debug variable + * @param value Signed integer value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -79,9 +79,9 @@ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param name Name of the debug variable + * @param value Signed integer value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -137,9 +137,9 @@ static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id * @brief Send a named_value_int message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param name Name of the debug variable + * @param value Signed integer value */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -208,7 +208,7 @@ static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbu /** * @brief Get field time_boot_ms from named_value_int message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) { @@ -218,7 +218,7 @@ static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlin /** * @brief Get field name from named_value_int message * - * @return Name of the debug variable + * @return Name of the debug variable */ static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) { @@ -228,7 +228,7 @@ static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_messag /** * @brief Get field value from named_value_int message * - * @return Signed integer value + * @return Signed integer value */ static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_nav_controller_output.h b/lib/main/MAVLink/common/mavlink_msg_nav_controller_output.h index 5f2d40f60d..2d9e8c0c5c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_nav_controller_output.h +++ b/lib/main/MAVLink/common/mavlink_msg_nav_controller_output.h @@ -3,17 +3,17 @@ #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 -MAVPACKED( + typedef struct __mavlink_nav_controller_output_t { - float nav_roll; /*< Current desired roll in degrees*/ - float nav_pitch; /*< Current desired pitch in degrees*/ - float alt_error; /*< Current altitude error in meters*/ - float aspd_error; /*< Current airspeed error in meters/second*/ - float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/ - int16_t nav_bearing; /*< Current desired heading in degrees*/ - int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/ - uint16_t wp_dist; /*< Distance to active MISSION in meters*/ -}) mavlink_nav_controller_output_t; + float nav_roll; /*< [deg] Current desired roll*/ + float nav_pitch; /*< [deg] Current desired pitch*/ + float alt_error; /*< [m] Current altitude error*/ + float aspd_error; /*< [m/s] Current airspeed error*/ + float xtrack_error; /*< [m] Current crosstrack error on x-y plane*/ + int16_t nav_bearing; /*< [deg] Current desired heading*/ + int16_t target_bearing; /*< [deg] Bearing to current waypoint/target*/ + uint16_t wp_dist; /*< [m] Distance to active waypoint*/ +} mavlink_nav_controller_output_t; #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN 26 @@ -32,12 +32,12 @@ typedef struct __mavlink_nav_controller_output_t { 8, \ { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ } \ } #else @@ -46,12 +46,12 @@ typedef struct __mavlink_nav_controller_output_t { 8, \ { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ } \ } #endif @@ -62,14 +62,14 @@ typedef struct __mavlink_nav_controller_output_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters + * @param nav_roll [deg] Current desired roll + * @param nav_pitch [deg] Current desired pitch + * @param nav_bearing [deg] Current desired heading + * @param target_bearing [deg] Bearing to current waypoint/target + * @param wp_dist [m] Distance to active waypoint + * @param alt_error [m] Current altitude error + * @param aspd_error [m/s] Current airspeed error + * @param xtrack_error [m] Current crosstrack error on x-y plane * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters + * @param nav_roll [deg] Current desired roll + * @param nav_pitch [deg] Current desired pitch + * @param nav_bearing [deg] Current desired heading + * @param target_bearing [deg] Bearing to current waypoint/target + * @param wp_dist [m] Distance to active waypoint + * @param alt_error [m] Current altitude error + * @param aspd_error [m/s] Current airspeed error + * @param xtrack_error [m] Current crosstrack error on x-y plane * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t sys * @brief Send a nav_controller_output message * @param chan MAVLink channel to send the message * - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters + * @param nav_roll [deg] Current desired roll + * @param nav_pitch [deg] Current desired pitch + * @param nav_bearing [deg] Current desired heading + * @param target_bearing [deg] Bearing to current waypoint/target + * @param wp_dist [m] Distance to active waypoint + * @param alt_error [m] Current altitude error + * @param aspd_error [m/s] Current airspeed error + * @param xtrack_error [m] Current crosstrack error on x-y plane */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -286,7 +286,7 @@ static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t /** * @brief Get field nav_roll from nav_controller_output message * - * @return Current desired roll in degrees + * @return [deg] Current desired roll */ static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) { @@ -296,7 +296,7 @@ static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink /** * @brief Get field nav_pitch from nav_controller_output message * - * @return Current desired pitch in degrees + * @return [deg] Current desired pitch */ static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) { @@ -306,7 +306,7 @@ static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlin /** * @brief Get field nav_bearing from nav_controller_output message * - * @return Current desired heading in degrees + * @return [deg] Current desired heading */ static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const ma /** * @brief Get field target_bearing from nav_controller_output message * - * @return Bearing to current MISSION/target in degrees + * @return [deg] Bearing to current waypoint/target */ static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const /** * @brief Get field wp_dist from nav_controller_output message * - * @return Distance to active MISSION in meters + * @return [m] Distance to active waypoint */ static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavli /** * @brief Get field alt_error from nav_controller_output message * - * @return Current altitude error in meters + * @return [m] Current altitude error */ static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlin /** * @brief Get field aspd_error from nav_controller_output message * - * @return Current airspeed error in meters/second + * @return [m/s] Current airspeed error */ static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavli /** * @brief Get field xtrack_error from nav_controller_output message * - * @return Current crosstrack error on x-y plane in meters + * @return [m] Current crosstrack error on x-y plane */ static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_optical_flow.h b/lib/main/MAVLink/common/mavlink_msg_optical_flow.h index 56b9a3c676..56082216f9 100755 --- a/lib/main/MAVLink/common/mavlink_msg_optical_flow.h +++ b/lib/main/MAVLink/common/mavlink_msg_optical_flow.h @@ -3,17 +3,17 @@ #define MAVLINK_MSG_ID_OPTICAL_FLOW 100 -MAVPACKED( + typedef struct __mavlink_optical_flow_t { - uint64_t time_usec; /*< Timestamp (UNIX)*/ - float flow_comp_m_x; /*< Flow in meters in x-sensor direction, angular-speed compensated*/ - float flow_comp_m_y; /*< Flow in meters in y-sensor direction, angular-speed compensated*/ - float ground_distance; /*< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance*/ - int16_t flow_x; /*< Flow in pixels * 10 in x-sensor direction (dezi-pixels)*/ - int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ -}) mavlink_optical_flow_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float flow_comp_m_x; /*< [m/s] Flow in x-sensor direction, angular-speed compensated*/ + float flow_comp_m_y; /*< [m/s] Flow in y-sensor direction, angular-speed compensated*/ + float ground_distance; /*< [m] Ground distance. Positive value: distance known. Negative value: Unknown distance*/ + int16_t flow_x; /*< [dpix] Flow in x-sensor direction*/ + int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ +} mavlink_optical_flow_t; #define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 #define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26 @@ -31,13 +31,13 @@ typedef struct __mavlink_optical_flow_t { "OPTICAL_FLOW", \ 8, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ + { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ } \ } #else @@ -45,13 +45,13 @@ typedef struct __mavlink_optical_flow_t { "OPTICAL_FLOW", \ 8, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ + { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ } \ } #endif @@ -62,14 +62,14 @@ typedef struct __mavlink_optical_flow_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param flow_x [dpix] Flow in x-sensor direction + * @param flow_y [dpix] Flow in y-sensor direction + * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -111,14 +111,14 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param flow_x [dpix] Flow in x-sensor direction + * @param flow_y [dpix] Flow in y-sensor direction + * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -186,14 +186,14 @@ static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, u * @brief Send a optical_flow message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param flow_x [dpix] Flow in x-sensor direction + * @param flow_y [dpix] Flow in y-sensor direction + * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -286,7 +286,7 @@ static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field time_usec from optical_flow message * - * @return Timestamp (UNIX) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) { @@ -296,7 +296,7 @@ static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_mess /** * @brief Get field sensor_id from optical_flow message * - * @return Sensor ID + * @return Sensor ID */ static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) { @@ -306,7 +306,7 @@ static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_messa /** * @brief Get field flow_x from optical_flow message * - * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @return [dpix] Flow in x-sensor direction */ static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) { @@ -316,7 +316,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_ /** * @brief Get field flow_y from optical_flow message * - * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @return [dpix] Flow in y-sensor direction */ static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) { @@ -326,7 +326,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_ /** * @brief Get field flow_comp_m_x from optical_flow message * - * @return Flow in meters in x-sensor direction, angular-speed compensated + * @return [m/s] Flow in x-sensor direction, angular-speed compensated */ static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) { @@ -336,7 +336,7 @@ static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_mes /** * @brief Get field flow_comp_m_y from optical_flow message * - * @return Flow in meters in y-sensor direction, angular-speed compensated + * @return [m/s] Flow in y-sensor direction, angular-speed compensated */ static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) { @@ -346,7 +346,7 @@ static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_mes /** * @brief Get field quality from optical_flow message * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality + * @return Optical flow quality / confidence. 0: bad, 255: maximum quality */ static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) { @@ -356,7 +356,7 @@ static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message /** * @brief Get field ground_distance from optical_flow message * - * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return [m] Ground distance. Positive value: distance known. Negative value: Unknown distance */ static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_optical_flow_rad.h b/lib/main/MAVLink/common/mavlink_msg_optical_flow_rad.h index c4326eb046..593533bf66 100755 --- a/lib/main/MAVLink/common/mavlink_msg_optical_flow_rad.h +++ b/lib/main/MAVLink/common/mavlink_msg_optical_flow_rad.h @@ -3,21 +3,21 @@ #define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106 -MAVPACKED( + typedef struct __mavlink_optical_flow_rad_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< RH rotation around X axis (rad)*/ - float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ - float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ - uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ - float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -}) mavlink_optical_flow_rad_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint32_t integration_time_us; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ + float integrated_x; /*< [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ + float integrated_y; /*< [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ + float integrated_xgyro; /*< [rad] RH rotation around X axis*/ + float integrated_ygyro; /*< [rad] RH rotation around Y axis*/ + float integrated_zgyro; /*< [rad] RH rotation around Z axis*/ + uint32_t time_delta_distance_us; /*< [us] Time since the distance was sampled.*/ + float distance; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/ + int16_t temperature; /*< [cdegC] Temperature*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ +} mavlink_optical_flow_rad_t; #define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44 #define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN 44 @@ -35,17 +35,17 @@ typedef struct __mavlink_optical_flow_rad_t { "OPTICAL_FLOW_RAD", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ } \ } #else @@ -53,17 +53,17 @@ typedef struct __mavlink_optical_flow_rad_t { "OPTICAL_FLOW_RAD", \ 12, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ } \ } #endif @@ -74,18 +74,18 @@ typedef struct __mavlink_optical_flow_rad_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro [rad] RH rotation around X axis + * @param integrated_ygyro [rad] RH rotation around Y axis + * @param integrated_zgyro [rad] RH rotation around Z axis + * @param temperature [cdegC] Temperature + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us [us] Time since the distance was sampled. + * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -135,18 +135,18 @@ static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro [rad] RH rotation around X axis + * @param integrated_ygyro [rad] RH rotation around Y axis + * @param integrated_zgyro [rad] RH rotation around Z axis + * @param temperature [cdegC] Temperature + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us [us] Time since the distance was sampled. + * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -222,18 +222,18 @@ static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_i * @brief Send a optical_flow_rad message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param sensor_id Sensor ID + * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro [rad] RH rotation around X axis + * @param integrated_ygyro [rad] RH rotation around Y axis + * @param integrated_zgyro [rad] RH rotation around Z axis + * @param temperature [cdegC] Temperature + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us [us] Time since the distance was sampled. + * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -342,7 +342,7 @@ static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgb /** * @brief Get field time_usec from optical_flow_rad message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_ /** * @brief Get field sensor_id from optical_flow_rad message * - * @return Sensor ID + * @return Sensor ID */ static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_m /** * @brief Get field integration_time_us from optical_flow_rad message * - * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. */ static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(cons /** * @brief Get field integrated_x from optical_flow_rad message * - * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @return [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) */ static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg) { @@ -382,7 +382,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_ /** * @brief Get field integrated_y from optical_flow_rad message * - * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @return [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) */ static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg) { @@ -392,7 +392,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_ /** * @brief Get field integrated_xgyro from optical_flow_rad message * - * @return RH rotation around X axis (rad) + * @return [rad] RH rotation around X axis */ static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg) { @@ -402,7 +402,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavl /** * @brief Get field integrated_ygyro from optical_flow_rad message * - * @return RH rotation around Y axis (rad) + * @return [rad] RH rotation around Y axis */ static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg) { @@ -412,7 +412,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavl /** * @brief Get field integrated_zgyro from optical_flow_rad message * - * @return RH rotation around Z axis (rad) + * @return [rad] RH rotation around Z axis */ static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg) { @@ -422,7 +422,7 @@ static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavl /** * @brief Get field temperature from optical_flow_rad message * - * @return Temperature * 100 in centi-degrees Celsius + * @return [cdegC] Temperature */ static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg) { @@ -432,7 +432,7 @@ static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink /** * @brief Get field quality from optical_flow_rad message * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality */ static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg) { @@ -442,7 +442,7 @@ static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_mes /** * @brief Get field time_delta_distance_us from optical_flow_rad message * - * @return Time in microseconds since the distance was sampled. + * @return [us] Time since the distance was sampled. */ static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg) { @@ -452,7 +452,7 @@ static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(c /** * @brief Get field distance from optical_flow_rad message * - * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. */ static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_param_ack_transaction.h b/lib/main/MAVLink/common/mavlink_msg_param_ack_transaction.h new file mode 100644 index 0000000000..404b084ab9 --- /dev/null +++ b/lib/main/MAVLink/common/mavlink_msg_param_ack_transaction.h @@ -0,0 +1,330 @@ +#pragma once +// MESSAGE PARAM_ACK_TRANSACTION PACKING + +#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION 19 + + +typedef struct __mavlink_param_ack_transaction_t { + float param_value; /*< Parameter value (new value if PARAM_ACCEPTED, current value otherwise)*/ + uint8_t target_system; /*< Id of system that sent PARAM_SET message.*/ + uint8_t target_component; /*< Id of system that sent PARAM_SET message.*/ + char param_id[16]; /*< Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Parameter type.*/ + uint8_t param_result; /*< Result code.*/ +} mavlink_param_ack_transaction_t; + +#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN 24 +#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN 24 +#define MAVLINK_MSG_ID_19_LEN 24 +#define MAVLINK_MSG_ID_19_MIN_LEN 24 + +#define MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC 137 +#define MAVLINK_MSG_ID_19_CRC 137 + +#define MAVLINK_MSG_PARAM_ACK_TRANSACTION_FIELD_PARAM_ID_LEN 16 + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_PARAM_ACK_TRANSACTION { \ + 19, \ + "PARAM_ACK_TRANSACTION", \ + 6, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_ack_transaction_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_ack_transaction_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_ack_transaction_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_ack_transaction_t, param_value) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_ack_transaction_t, param_type) }, \ + { "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_param_ack_transaction_t, param_result) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_PARAM_ACK_TRANSACTION { \ + "PARAM_ACK_TRANSACTION", \ + 6, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_ack_transaction_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_ack_transaction_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_ack_transaction_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_ack_transaction_t, param_value) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_ack_transaction_t, param_type) }, \ + { "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_param_ack_transaction_t, param_result) }, \ + } \ +} +#endif + +/** + * @brief Pack a param_ack_transaction message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system Id of system that sent PARAM_SET message. + * @param target_component Id of system that sent PARAM_SET message. + * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Parameter value (new value if PARAM_ACCEPTED, current value otherwise) + * @param param_type Parameter type. + * @param param_result Result code. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_ack_transaction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type, uint8_t param_result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_uint8_t(buf, 23, param_result); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN); +#else + mavlink_param_ack_transaction_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + packet.param_result = param_result; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +} + +/** + * @brief Pack a param_ack_transaction message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system Id of system that sent PARAM_SET message. + * @param target_component Id of system that sent PARAM_SET message. + * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Parameter value (new value if PARAM_ACCEPTED, current value otherwise) + * @param param_type Parameter type. + * @param param_result Result code. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_ack_transaction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type,uint8_t param_result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_uint8_t(buf, 23, param_result); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN); +#else + mavlink_param_ack_transaction_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + packet.param_result = param_result; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +} + +/** + * @brief Encode a param_ack_transaction struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_ack_transaction C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_ack_transaction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ack_transaction_t* param_ack_transaction) +{ + return mavlink_msg_param_ack_transaction_pack(system_id, component_id, msg, param_ack_transaction->target_system, param_ack_transaction->target_component, param_ack_transaction->param_id, param_ack_transaction->param_value, param_ack_transaction->param_type, param_ack_transaction->param_result); +} + +/** + * @brief Encode a param_ack_transaction struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_ack_transaction C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_ack_transaction_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ack_transaction_t* param_ack_transaction) +{ + return mavlink_msg_param_ack_transaction_pack_chan(system_id, component_id, chan, msg, param_ack_transaction->target_system, param_ack_transaction->target_component, param_ack_transaction->param_id, param_ack_transaction->param_value, param_ack_transaction->param_type, param_ack_transaction->param_result); +} + +/** + * @brief Send a param_ack_transaction message + * @param chan MAVLink channel to send the message + * + * @param target_system Id of system that sent PARAM_SET message. + * @param target_component Id of system that sent PARAM_SET message. + * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Parameter value (new value if PARAM_ACCEPTED, current value otherwise) + * @param param_type Parameter type. + * @param param_result Result code. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_ack_transaction_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type, uint8_t param_result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_uint8_t(buf, 23, param_result); + _mav_put_char_array(buf, 6, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +#else + mavlink_param_ack_transaction_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + packet.param_result = param_result; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, (const char *)&packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +#endif +} + +/** + * @brief Send a param_ack_transaction message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_param_ack_transaction_send_struct(mavlink_channel_t chan, const mavlink_param_ack_transaction_t* param_ack_transaction) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_param_ack_transaction_send(chan, param_ack_transaction->target_system, param_ack_transaction->target_component, param_ack_transaction->param_id, param_ack_transaction->param_value, param_ack_transaction->param_type, param_ack_transaction->param_result); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, (const char *)param_ack_transaction, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +#endif +} + +#if MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_ack_transaction_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type, uint8_t param_result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_uint8_t(buf, 23, param_result); + _mav_put_char_array(buf, 6, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, buf, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +#else + mavlink_param_ack_transaction_t *packet = (mavlink_param_ack_transaction_t *)msgbuf; + packet->param_value = param_value; + packet->target_system = target_system; + packet->target_component = target_component; + packet->param_type = param_type; + packet->param_result = param_result; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION, (const char *)packet, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_CRC); +#endif +} +#endif + +#endif + +// MESSAGE PARAM_ACK_TRANSACTION UNPACKING + + +/** + * @brief Get field target_system from param_ack_transaction message + * + * @return Id of system that sent PARAM_SET message. + */ +static inline uint8_t mavlink_msg_param_ack_transaction_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from param_ack_transaction message + * + * @return Id of system that sent PARAM_SET message. + */ +static inline uint8_t mavlink_msg_param_ack_transaction_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field param_id from param_ack_transaction message + * + * @return Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_ack_transaction_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 6); +} + +/** + * @brief Get field param_value from param_ack_transaction message + * + * @return Parameter value (new value if PARAM_ACCEPTED, current value otherwise) + */ +static inline float mavlink_msg_param_ack_transaction_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_ack_transaction message + * + * @return Parameter type. + */ +static inline uint8_t mavlink_msg_param_ack_transaction_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 22); +} + +/** + * @brief Get field param_result from param_ack_transaction message + * + * @return Result code. + */ +static inline uint8_t mavlink_msg_param_ack_transaction_get_param_result(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 23); +} + +/** + * @brief Decode a param_ack_transaction message into a struct + * + * @param msg The message to decode + * @param param_ack_transaction C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_ack_transaction_decode(const mavlink_message_t* msg, mavlink_param_ack_transaction_t* param_ack_transaction) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + param_ack_transaction->param_value = mavlink_msg_param_ack_transaction_get_param_value(msg); + param_ack_transaction->target_system = mavlink_msg_param_ack_transaction_get_target_system(msg); + param_ack_transaction->target_component = mavlink_msg_param_ack_transaction_get_target_component(msg); + mavlink_msg_param_ack_transaction_get_param_id(msg, param_ack_transaction->param_id); + param_ack_transaction->param_type = mavlink_msg_param_ack_transaction_get_param_type(msg); + param_ack_transaction->param_result = mavlink_msg_param_ack_transaction_get_param_result(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN? msg->len : MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN; + memset(param_ack_transaction, 0, MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_LEN); + memcpy(param_ack_transaction, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/lib/main/MAVLink/common/mavlink_msg_param_map_rc.h b/lib/main/MAVLink/common/mavlink_msg_param_map_rc.h index 5b64b7f890..5bea16c7ce 100755 --- a/lib/main/MAVLink/common/mavlink_msg_param_map_rc.h +++ b/lib/main/MAVLink/common/mavlink_msg_param_map_rc.h @@ -3,18 +3,18 @@ #define MAVLINK_MSG_ID_PARAM_MAP_RC 50 -MAVPACKED( + typedef struct __mavlink_param_map_rc_t { - float param_value0; /*< Initial parameter value*/ - float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ - float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ - float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.*/ -}) mavlink_param_map_rc_t; + float param_value0; /*< Initial parameter value*/ + float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ + float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ + float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ + int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.*/ +} mavlink_param_map_rc_t; #define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 #define MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN 37 @@ -31,30 +31,30 @@ typedef struct __mavlink_param_map_rc_t { 50, \ "PARAM_MAP_RC", \ 9, \ - { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ + { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ + { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ "PARAM_MAP_RC", \ 9, \ - { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ + { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ + { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ } \ } #endif @@ -65,15 +65,15 @@ typedef struct __mavlink_param_map_rc_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -115,15 +115,15 @@ static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -191,15 +191,15 @@ static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, u * @brief Send a param_map_rc message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -292,7 +292,7 @@ static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field target_system from param_map_rc message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_m /** * @brief Get field target_component from param_map_rc message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlin /** * @brief Get field param_id from param_map_rc message * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string */ static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id) { @@ -322,7 +322,7 @@ static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_messa /** * @brief Get field param_index from param_map_rc message * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. */ static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_mes /** * @brief Get field parameter_rc_channel_index from param_map_rc message * - * @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @return Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. */ static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg) { @@ -342,7 +342,7 @@ static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(co /** * @brief Get field param_value0 from param_map_rc message * - * @return Initial parameter value + * @return Initial parameter value */ static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_mess /** * @brief Get field scale from param_map_rc message * - * @return Scale, maps the RC range [-1, 1] to a parameter value + * @return Scale, maps the RC range [-1, 1] to a parameter value */ static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* /** * @brief Get field param_value_min from param_map_rc message * - * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) */ static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_m /** * @brief Get field param_value_max from param_map_rc message * - * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) */ static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_param_request_list.h b/lib/main/MAVLink/common/mavlink_msg_param_request_list.h index 2c5da24bc6..e8ad2157d4 100755 --- a/lib/main/MAVLink/common/mavlink_msg_param_request_list.h +++ b/lib/main/MAVLink/common/mavlink_msg_param_request_list.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 -MAVPACKED( + typedef struct __mavlink_param_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_param_request_list_t; + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_param_request_list_t; #define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 #define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN 2 @@ -44,8 +44,8 @@ typedef struct __mavlink_param_request_list_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, ui * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system * @brief Send a param_request_list message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID + * @param target_system System ID + * @param target_component Component ID */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *ms /** * @brief Get field target_system from param_request_list message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mav /** * @brief Get field target_component from param_request_list message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_param_request_read.h b/lib/main/MAVLink/common/mavlink_msg_param_request_read.h index 5381596727..92a3e86685 100755 --- a/lib/main/MAVLink/common/mavlink_msg_param_request_read.h +++ b/lib/main/MAVLink/common/mavlink_msg_param_request_read.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 -MAVPACKED( + typedef struct __mavlink_param_request_read_t { - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ -}) mavlink_param_request_read_t; + int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ +} mavlink_param_request_read_t; #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN 20 @@ -26,20 +26,20 @@ typedef struct __mavlink_param_request_read_t { 20, \ "PARAM_REQUEST_READ", \ 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ "PARAM_REQUEST_READ", \ 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_param_request_read_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -85,10 +85,10 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -146,10 +146,10 @@ static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system * @brief Send a param_request_read message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -222,7 +222,7 @@ static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *ms /** * @brief Get field target_system from param_request_read message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) { @@ -232,7 +232,7 @@ static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mav /** * @brief Get field target_component from param_request_read message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) { @@ -242,7 +242,7 @@ static inline uint8_t mavlink_msg_param_request_read_get_target_component(const /** * @brief Get field param_id from param_request_read message * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string */ static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) { @@ -252,7 +252,7 @@ static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink /** * @brief Get field param_index from param_request_read message * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) */ static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_param_set.h b/lib/main/MAVLink/common/mavlink_msg_param_set.h index cc73109bce..72039bca9a 100755 --- a/lib/main/MAVLink/common/mavlink_msg_param_set.h +++ b/lib/main/MAVLink/common/mavlink_msg_param_set.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_PARAM_SET 23 -MAVPACKED( + typedef struct __mavlink_param_set_t { - float param_value; /*< Onboard parameter value*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ -}) mavlink_param_set_t; + float param_value; /*< Onboard parameter value*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Onboard parameter type.*/ +} mavlink_param_set_t; #define MAVLINK_MSG_ID_PARAM_SET_LEN 23 #define MAVLINK_MSG_ID_PARAM_SET_MIN_LEN 23 @@ -27,10 +27,10 @@ typedef struct __mavlink_param_set_t { 23, \ "PARAM_SET", \ 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ } \ } @@ -38,10 +38,10 @@ typedef struct __mavlink_param_set_t { #define MAVLINK_MESSAGE_INFO_PARAM_SET { \ "PARAM_SET", \ 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ } \ } @@ -53,11 +53,11 @@ typedef struct __mavlink_param_set_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint * @brief Send a param_set message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field target_system from param_set message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) { @@ -246,7 +246,7 @@ static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_mess /** * @brief Get field target_component from param_set message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) { @@ -256,7 +256,7 @@ static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_m /** * @brief Get field param_id from param_set message * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string */ static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) { @@ -266,7 +266,7 @@ static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_ /** * @brief Get field param_value from param_set message * - * @return Onboard parameter value + * @return Onboard parameter value */ static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_ /** * @brief Get field param_type from param_set message * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @return Onboard parameter type. */ static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_param_value.h b/lib/main/MAVLink/common/mavlink_msg_param_value.h index e2cb891d02..e487917cc0 100755 --- a/lib/main/MAVLink/common/mavlink_msg_param_value.h +++ b/lib/main/MAVLink/common/mavlink_msg_param_value.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_PARAM_VALUE 22 -MAVPACKED( + typedef struct __mavlink_param_value_t { - float param_value; /*< Onboard parameter value*/ - uint16_t param_count; /*< Total number of onboard parameters*/ - uint16_t param_index; /*< Index of this onboard parameter*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ -}) mavlink_param_value_t; + float param_value; /*< Onboard parameter value*/ + uint16_t param_count; /*< Total number of onboard parameters*/ + uint16_t param_index; /*< Index of this onboard parameter*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Onboard parameter type.*/ +} mavlink_param_value_t; #define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 #define MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN 25 @@ -27,22 +27,22 @@ typedef struct __mavlink_param_value_t { 22, \ "PARAM_VALUE", \ 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ "PARAM_VALUE", \ 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ } \ } #endif @@ -53,11 +53,11 @@ typedef struct __mavlink_param_value_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, ui * @brief Send a param_value message * @param chan MAVLink channel to send the message * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field param_id from param_value message * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string */ static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) { @@ -246,7 +246,7 @@ static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_messag /** * @brief Get field param_value from param_value message * - * @return Onboard parameter value + * @return Onboard parameter value */ static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) { @@ -256,7 +256,7 @@ static inline float mavlink_msg_param_value_get_param_value(const mavlink_messag /** * @brief Get field param_type from param_value message * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @return Onboard parameter type. */ static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) { @@ -266,7 +266,7 @@ static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_messa /** * @brief Get field param_count from param_value message * - * @return Total number of onboard parameters + * @return Total number of onboard parameters */ static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_mes /** * @brief Get field param_index from param_value message * - * @return Index of this onboard parameter + * @return Index of this onboard parameter */ static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_ping.h b/lib/main/MAVLink/common/mavlink_msg_ping.h index 1e18bc6726..1e5508d442 100755 --- a/lib/main/MAVLink/common/mavlink_msg_ping.h +++ b/lib/main/MAVLink/common/mavlink_msg_ping.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_PING 4 -MAVPACKED( + typedef struct __mavlink_ping_t { - uint64_t time_usec; /*< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)*/ - uint32_t seq; /*< PING sequence*/ - uint8_t target_system; /*< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system*/ - uint8_t target_component; /*< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system*/ -}) mavlink_ping_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint32_t seq; /*< PING sequence*/ + uint8_t target_system; /*< 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system*/ + uint8_t target_component; /*< 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.*/ +} mavlink_ping_t; #define MAVLINK_MSG_ID_PING_LEN 14 #define MAVLINK_MSG_ID_PING_MIN_LEN 14 @@ -50,10 +50,10 @@ typedef struct __mavlink_ping_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t c * @brief Send a ping message * @param chan MAVLink channel to send the message * - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_ /** * @brief Get field time_usec from ping message * - * @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* m /** * @brief Get field seq from ping message * - * @return PING sequence + * @return PING sequence */ static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) /** * @brief Get field target_system from ping message * - * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system */ static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t /** * @brief Get field target_component from ping message * - * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. */ static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_position_target_global_int.h b/lib/main/MAVLink/common/mavlink_msg_position_target_global_int.h index 160a5fa4f0..93386fab75 100755 --- a/lib/main/MAVLink/common/mavlink_msg_position_target_global_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_position_target_global_int.h @@ -3,23 +3,23 @@ #define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 -MAVPACKED( + typedef struct __mavlink_position_target_global_int_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ - int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ - float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -}) mavlink_position_target_global_int_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ + int32_t lat_int; /*< [degE7] X Position in WGS84 frame*/ + int32_t lon_int; /*< [degE7] Y Position in WGS84 frame*/ + float alt; /*< [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)*/ + float vx; /*< [m/s] X velocity in NED frame*/ + float vy; /*< [m/s] Y velocity in NED frame*/ + float vz; /*< [m/s] Z velocity in NED frame*/ + float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< [rad] yaw setpoint*/ + float yaw_rate; /*< [rad/s] yaw rate setpoint*/ + uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ +} mavlink_position_target_global_int_t; #define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 #define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN 51 @@ -37,6 +37,8 @@ typedef struct __mavlink_position_target_global_int_t { "POSITION_TARGET_GLOBAL_INT", \ 14, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ @@ -48,8 +50,6 @@ typedef struct __mavlink_position_target_global_int_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ } \ } #else @@ -57,6 +57,8 @@ typedef struct __mavlink_position_target_global_int_t { "POSITION_TARGET_GLOBAL_INT", \ 14, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ @@ -68,8 +70,6 @@ typedef struct __mavlink_position_target_global_int_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ } \ } #endif @@ -80,20 +80,20 @@ typedef struct __mavlink_position_target_global_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param lat_int [degE7] X Position in WGS84 frame + * @param lon_int [degE7] Y Position in WGS84 frame + * @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t syste * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param lat_int [degE7] X Position in WGS84 frame + * @param lon_int [degE7] Y Position in WGS84 frame + * @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_ * @brief Send a position_target_global_int message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param lat_int [degE7] X Position in WGS84 frame + * @param lon_int [degE7] Y Position in WGS84 frame + * @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -370,7 +370,7 @@ static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_messa /** * @brief Get field time_boot_ms from position_target_global_int message * - * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @return [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. */ static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(c /** * @brief Get field coordinate_frame from position_target_global_int message * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 */ static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) { @@ -390,7 +390,7 @@ static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_fram /** * @brief Get field type_mask from position_target_global_int message * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @return Bitmap to indicate which dimensions should be ignored by the vehicle. */ static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg) { @@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(cons /** * @brief Get field lat_int from position_target_global_int message * - * @return X Position in WGS84 frame in 1e7 * meters + * @return [degE7] X Position in WGS84 frame */ static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg) { @@ -410,7 +410,7 @@ static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const m /** * @brief Get field lon_int from position_target_global_int message * - * @return Y Position in WGS84 frame in 1e7 * meters + * @return [degE7] Y Position in WGS84 frame */ static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const m /** * @brief Get field alt from position_target_global_int message * - * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @return [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) */ static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg) { @@ -430,7 +430,7 @@ static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink /** * @brief Get field vx from position_target_global_int message * - * @return X velocity in NED frame in meter / s + * @return [m/s] X velocity in NED frame */ static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg) { @@ -440,7 +440,7 @@ static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_ /** * @brief Get field vy from position_target_global_int message * - * @return Y velocity in NED frame in meter / s + * @return [m/s] Y velocity in NED frame */ static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_ /** * @brief Get field vz from position_target_global_int message * - * @return Z velocity in NED frame in meter / s + * @return [m/s] Z velocity in NED frame */ static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg) { @@ -460,7 +460,7 @@ static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_ /** * @brief Get field afx from position_target_global_int message * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg) { @@ -470,7 +470,7 @@ static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink /** * @brief Get field afy from position_target_global_int message * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg) { @@ -480,7 +480,7 @@ static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink /** * @brief Get field afz from position_target_global_int message * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg) { @@ -490,7 +490,7 @@ static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink /** * @brief Get field yaw from position_target_global_int message * - * @return yaw setpoint in rad + * @return [rad] yaw setpoint */ static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg) { @@ -500,7 +500,7 @@ static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink /** * @brief Get field yaw_rate from position_target_global_int message * - * @return yaw rate setpoint in rad/s + * @return [rad/s] yaw rate setpoint */ static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_position_target_local_ned.h b/lib/main/MAVLink/common/mavlink_msg_position_target_local_ned.h index 3464e9aad8..f3cfde26e3 100755 --- a/lib/main/MAVLink/common/mavlink_msg_position_target_local_ned.h +++ b/lib/main/MAVLink/common/mavlink_msg_position_target_local_ned.h @@ -3,23 +3,23 @@ #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85 -MAVPACKED( + typedef struct __mavlink_position_target_local_ned_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float x; /*< X Position in NED frame in meters*/ - float y; /*< Y Position in NED frame in meters*/ - float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -}) mavlink_position_target_local_ned_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float x; /*< [m] X Position in NED frame*/ + float y; /*< [m] Y Position in NED frame*/ + float z; /*< [m] Z Position in NED frame (note, altitude is negative in NED)*/ + float vx; /*< [m/s] X velocity in NED frame*/ + float vy; /*< [m/s] Y velocity in NED frame*/ + float vz; /*< [m/s] Z velocity in NED frame*/ + float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< [rad] yaw setpoint*/ + float yaw_rate; /*< [rad/s] yaw rate setpoint*/ + uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ +} mavlink_position_target_local_ned_t; #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN 51 @@ -37,6 +37,8 @@ typedef struct __mavlink_position_target_local_ned_t { "POSITION_TARGET_LOCAL_NED", \ 14, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ @@ -48,8 +50,6 @@ typedef struct __mavlink_position_target_local_ned_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ } \ } #else @@ -57,6 +57,8 @@ typedef struct __mavlink_position_target_local_ned_t { "POSITION_TARGET_LOCAL_NED", \ 14, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ @@ -68,8 +70,6 @@ typedef struct __mavlink_position_target_local_ned_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ } \ } #endif @@ -80,20 +80,20 @@ typedef struct __mavlink_position_target_local_ned_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param x [m] X Position in NED frame + * @param y [m] Y Position in NED frame + * @param z [m] Z Position in NED frame (note, altitude is negative in NED) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -147,20 +147,20 @@ static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param x [m] X Position in NED frame + * @param y [m] Y Position in NED frame + * @param z [m] Z Position in NED frame (note, altitude is negative in NED) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -240,20 +240,20 @@ static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t * @brief Send a position_target_local_ned message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param x [m] X Position in NED frame + * @param y [m] Y Position in NED frame + * @param z [m] Z Position in NED frame (note, altitude is negative in NED) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -370,7 +370,7 @@ static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_messag /** * @brief Get field time_boot_ms from position_target_local_ned message * - * @return Timestamp in milliseconds since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(co /** * @brief Get field coordinate_frame from position_target_local_ned message * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 */ static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) { @@ -390,7 +390,7 @@ static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame /** * @brief Get field type_mask from position_target_local_ned message * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @return Bitmap to indicate which dimensions should be ignored by the vehicle. */ static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) { @@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const /** * @brief Get field x from position_target_local_ned message * - * @return X Position in NED frame in meters + * @return [m] X Position in NED frame */ static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg) { @@ -410,7 +410,7 @@ static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_me /** * @brief Get field y from position_target_local_ned message * - * @return Y Position in NED frame in meters + * @return [m] Y Position in NED frame */ static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_me /** * @brief Get field z from position_target_local_ned message * - * @return Z Position in NED frame in meters (note, altitude is negative in NED) + * @return [m] Z Position in NED frame (note, altitude is negative in NED) */ static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg) { @@ -430,7 +430,7 @@ static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_me /** * @brief Get field vx from position_target_local_ned message * - * @return X velocity in NED frame in meter / s + * @return [m/s] X velocity in NED frame */ static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg) { @@ -440,7 +440,7 @@ static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_m /** * @brief Get field vy from position_target_local_ned message * - * @return Y velocity in NED frame in meter / s + * @return [m/s] Y velocity in NED frame */ static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_m /** * @brief Get field vz from position_target_local_ned message * - * @return Z velocity in NED frame in meter / s + * @return [m/s] Z velocity in NED frame */ static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg) { @@ -460,7 +460,7 @@ static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_m /** * @brief Get field afx from position_target_local_ned message * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg) { @@ -470,7 +470,7 @@ static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_ /** * @brief Get field afy from position_target_local_ned message * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg) { @@ -480,7 +480,7 @@ static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_ /** * @brief Get field afz from position_target_local_ned message * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg) { @@ -490,7 +490,7 @@ static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_ /** * @brief Get field yaw from position_target_local_ned message * - * @return yaw setpoint in rad + * @return [rad] yaw setpoint */ static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg) { @@ -500,7 +500,7 @@ static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_ /** * @brief Get field yaw_rate from position_target_local_ned message * - * @return yaw rate setpoint in rad/s + * @return [rad/s] yaw rate setpoint */ static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_power_status.h b/lib/main/MAVLink/common/mavlink_msg_power_status.h index dca62b5868..67567680cd 100755 --- a/lib/main/MAVLink/common/mavlink_msg_power_status.h +++ b/lib/main/MAVLink/common/mavlink_msg_power_status.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_POWER_STATUS 125 -MAVPACKED( + typedef struct __mavlink_power_status_t { - uint16_t Vcc; /*< 5V rail voltage in millivolts*/ - uint16_t Vservo; /*< servo rail voltage in millivolts*/ - uint16_t flags; /*< power supply status flags (see MAV_POWER_STATUS enum)*/ -}) mavlink_power_status_t; + uint16_t Vcc; /*< [mV] 5V rail voltage.*/ + uint16_t Vservo; /*< [mV] Servo rail voltage.*/ + uint16_t flags; /*< Bitmap of power supply status flags.*/ +} mavlink_power_status_t; #define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 #define MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN 6 @@ -47,9 +47,9 @@ typedef struct __mavlink_power_status_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @param Vcc [mV] 5V rail voltage. + * @param Vservo [mV] Servo rail voltage. + * @param flags Bitmap of power supply status flags. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @param Vcc [mV] 5V rail voltage. + * @param Vservo [mV] Servo rail voltage. + * @param flags Bitmap of power supply status flags. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, u * @brief Send a power_status message * @param chan MAVLink channel to send the message * - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @param Vcc [mV] 5V rail voltage. + * @param Vservo [mV] Servo rail voltage. + * @param flags Bitmap of power supply status flags. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field Vcc from power_status message * - * @return 5V rail voltage in millivolts + * @return [mV] 5V rail voltage. */ static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* /** * @brief Get field Vservo from power_status message * - * @return servo rail voltage in millivolts + * @return [mV] Servo rail voltage. */ static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message /** * @brief Get field flags from power_status message * - * @return power supply status flags (see MAV_POWER_STATUS enum) + * @return Bitmap of power supply status flags. */ static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_radio_status.h b/lib/main/MAVLink/common/mavlink_msg_radio_status.h index 8d266bb4e8..8983a20a4c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_radio_status.h +++ b/lib/main/MAVLink/common/mavlink_msg_radio_status.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_RADIO_STATUS 109 -MAVPACKED( + typedef struct __mavlink_radio_status_t { - uint16_t rxerrors; /*< Receive errors*/ - uint16_t fixed; /*< Count of error corrected packets*/ - uint8_t rssi; /*< Local signal strength*/ - uint8_t remrssi; /*< Remote signal strength*/ - uint8_t txbuf; /*< Remaining free buffer space in percent.*/ - uint8_t noise; /*< Background noise level*/ - uint8_t remnoise; /*< Remote background noise level*/ -}) mavlink_radio_status_t; + uint16_t rxerrors; /*< Count of radio packet receive errors (since boot).*/ + uint16_t fixed; /*< Count of error corrected radio packets (since boot).*/ + uint8_t rssi; /*< Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/ + uint8_t remrssi; /*< Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/ + uint8_t txbuf; /*< [%] Remaining free transmitter buffer space.*/ + uint8_t noise; /*< Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.*/ + uint8_t remnoise; /*< Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.*/ +} mavlink_radio_status_t; #define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 #define MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN 9 @@ -29,26 +29,26 @@ typedef struct __mavlink_radio_status_t { 109, \ "RADIO_STATUS", \ 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ + { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ + { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ "RADIO_STATUS", \ 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ + { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ + { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ } \ } #endif @@ -59,13 +59,13 @@ typedef struct __mavlink_radio_status_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param rssi Local signal strength - * @param remrssi Remote signal strength - * @param txbuf Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets + * @param rssi Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + * @param remrssi Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + * @param txbuf [%] Remaining free transmitter buffer space. + * @param noise Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + * @param remnoise Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + * @param rxerrors Count of radio packet receive errors (since boot). + * @param fixed Count of error corrected radio packets (since boot). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param rssi Local signal strength - * @param remrssi Remote signal strength - * @param txbuf Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets + * @param rssi Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + * @param remrssi Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + * @param txbuf [%] Remaining free transmitter buffer space. + * @param noise Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + * @param remnoise Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + * @param rxerrors Count of radio packet receive errors (since boot). + * @param fixed Count of error corrected radio packets (since boot). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, u * @brief Send a radio_status message * @param chan MAVLink channel to send the message * - * @param rssi Local signal strength - * @param remrssi Remote signal strength - * @param txbuf Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets + * @param rssi Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + * @param remrssi Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + * @param txbuf [%] Remaining free transmitter buffer space. + * @param noise Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + * @param remnoise Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + * @param rxerrors Count of radio packet receive errors (since boot). + * @param fixed Count of error corrected radio packets (since boot). */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field rssi from radio_status message * - * @return Local signal strength + * @return Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* /** * @brief Get field remrssi from radio_status message * - * @return Remote signal strength + * @return Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message /** * @brief Get field txbuf from radio_status message * - * @return Remaining free buffer space in percent. + * @return [%] Remaining free transmitter buffer space. */ static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t /** * @brief Get field noise from radio_status message * - * @return Background noise level + * @return Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t /** * @brief Get field remnoise from radio_status message * - * @return Remote background noise level + * @return Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_messag /** * @brief Get field rxerrors from radio_status message * - * @return Receive errors + * @return Count of radio packet receive errors (since boot). */ static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_messa /** * @brief Get field fixed from radio_status message * - * @return Count of error corrected packets + * @return Count of error corrected radio packets (since boot). */ static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_raw_imu.h b/lib/main/MAVLink/common/mavlink_msg_raw_imu.h index 23833bc8b3..0e0cf7141c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_raw_imu.h +++ b/lib/main/MAVLink/common/mavlink_msg_raw_imu.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_RAW_IMU 27 -MAVPACKED( + typedef struct __mavlink_raw_imu_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int16_t xacc; /*< X acceleration (raw)*/ - int16_t yacc; /*< Y acceleration (raw)*/ - int16_t zacc; /*< Z acceleration (raw)*/ - int16_t xgyro; /*< Angular speed around X axis (raw)*/ - int16_t ygyro; /*< Angular speed around Y axis (raw)*/ - int16_t zgyro; /*< Angular speed around Z axis (raw)*/ - int16_t xmag; /*< X Magnetic field (raw)*/ - int16_t ymag; /*< Y Magnetic field (raw)*/ - int16_t zmag; /*< Z Magnetic field (raw)*/ -}) mavlink_raw_imu_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + int16_t xacc; /*< X acceleration (raw)*/ + int16_t yacc; /*< Y acceleration (raw)*/ + int16_t zacc; /*< Z acceleration (raw)*/ + int16_t xgyro; /*< Angular speed around X axis (raw)*/ + int16_t ygyro; /*< Angular speed around Y axis (raw)*/ + int16_t zgyro; /*< Angular speed around Z axis (raw)*/ + int16_t xmag; /*< X Magnetic field (raw)*/ + int16_t ymag; /*< Y Magnetic field (raw)*/ + int16_t zmag; /*< Z Magnetic field (raw)*/ +} mavlink_raw_imu_t; #define MAVLINK_MSG_ID_RAW_IMU_LEN 26 #define MAVLINK_MSG_ID_RAW_IMU_MIN_LEN 26 @@ -68,16 +68,16 @@ typedef struct __mavlink_raw_imu_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_ * @brief Send a raw_imu message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavli /** * @brief Get field time_usec from raw_imu message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t /** * @brief Get field xacc from raw_imu message * - * @return X acceleration (raw) + * @return X acceleration (raw) */ static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) /** * @brief Get field yacc from raw_imu message * - * @return Y acceleration (raw) + * @return Y acceleration (raw) */ static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) /** * @brief Get field zacc from raw_imu message * - * @return Z acceleration (raw) + * @return Z acceleration (raw) */ static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) /** * @brief Get field xgyro from raw_imu message * - * @return Angular speed around X axis (raw) + * @return Angular speed around X axis (raw) */ static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg /** * @brief Get field ygyro from raw_imu message * - * @return Angular speed around Y axis (raw) + * @return Angular speed around Y axis (raw) */ static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg /** * @brief Get field zgyro from raw_imu message * - * @return Angular speed around Z axis (raw) + * @return Angular speed around Z axis (raw) */ static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg /** * @brief Get field xmag from raw_imu message * - * @return X Magnetic field (raw) + * @return X Magnetic field (raw) */ static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) /** * @brief Get field ymag from raw_imu message * - * @return Y Magnetic field (raw) + * @return Y Magnetic field (raw) */ static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) /** * @brief Get field zmag from raw_imu message * - * @return Z Magnetic field (raw) + * @return Z Magnetic field (raw) */ static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_raw_pressure.h b/lib/main/MAVLink/common/mavlink_msg_raw_pressure.h index 2d2ead97ec..9b80a848e7 100755 --- a/lib/main/MAVLink/common/mavlink_msg_raw_pressure.h +++ b/lib/main/MAVLink/common/mavlink_msg_raw_pressure.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_RAW_PRESSURE 28 -MAVPACKED( + typedef struct __mavlink_raw_pressure_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int16_t press_abs; /*< Absolute pressure (raw)*/ - int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistant)*/ - int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistant)*/ - int16_t temperature; /*< Raw Temperature measurement (raw)*/ -}) mavlink_raw_pressure_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + int16_t press_abs; /*< Absolute pressure (raw)*/ + int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistent)*/ + int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistent)*/ + int16_t temperature; /*< Raw Temperature measurement (raw)*/ +} mavlink_raw_pressure_t; #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 #define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16 @@ -53,11 +53,11 @@ typedef struct __mavlink_raw_pressure_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent) + * @param temperature Raw Temperature measurement (raw) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -93,11 +93,11 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent) + * @param temperature Raw Temperature measurement (raw) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -159,11 +159,11 @@ static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, u * @brief Send a raw_pressure message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent) + * @param temperature Raw Temperature measurement (raw) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -244,7 +244,7 @@ static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field time_usec from raw_pressure message * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) { @@ -254,7 +254,7 @@ static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_mess /** * @brief Get field press_abs from raw_pressure message * - * @return Absolute pressure (raw) + * @return Absolute pressure (raw) */ static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) { @@ -264,7 +264,7 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_messa /** * @brief Get field press_diff1 from raw_pressure message * - * @return Differential pressure 1 (raw, 0 if nonexistant) + * @return Differential pressure 1 (raw, 0 if nonexistent) */ static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) { @@ -274,7 +274,7 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_mes /** * @brief Get field press_diff2 from raw_pressure message * - * @return Differential pressure 2 (raw, 0 if nonexistant) + * @return Differential pressure 2 (raw, 0 if nonexistent) */ static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) { @@ -284,7 +284,7 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_mes /** * @brief Get field temperature from raw_pressure message * - * @return Raw Temperature measurement (raw) + * @return Raw Temperature measurement (raw) */ static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_rc_channels.h b/lib/main/MAVLink/common/mavlink_msg_rc_channels.h index f7637379b4..f4694f1b89 100755 --- a/lib/main/MAVLink/common/mavlink_msg_rc_channels.h +++ b/lib/main/MAVLink/common/mavlink_msg_rc_channels.h @@ -3,30 +3,30 @@ #define MAVLINK_MSG_ID_RC_CHANNELS 65 -MAVPACKED( + typedef struct __mavlink_rc_channels_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan9_raw; /*< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan10_raw; /*< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan11_raw; /*< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan12_raw; /*< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan13_raw; /*< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan14_raw; /*< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan15_raw; /*< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan16_raw; /*< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan17_raw; /*< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan18_raw; /*< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + uint16_t chan1_raw; /*< [us] RC channel 1 value.*/ + uint16_t chan2_raw; /*< [us] RC channel 2 value.*/ + uint16_t chan3_raw; /*< [us] RC channel 3 value.*/ + uint16_t chan4_raw; /*< [us] RC channel 4 value.*/ + uint16_t chan5_raw; /*< [us] RC channel 5 value.*/ + uint16_t chan6_raw; /*< [us] RC channel 6 value.*/ + uint16_t chan7_raw; /*< [us] RC channel 7 value.*/ + uint16_t chan8_raw; /*< [us] RC channel 8 value.*/ + uint16_t chan9_raw; /*< [us] RC channel 9 value.*/ + uint16_t chan10_raw; /*< [us] RC channel 10 value.*/ + uint16_t chan11_raw; /*< [us] RC channel 11 value.*/ + uint16_t chan12_raw; /*< [us] RC channel 12 value.*/ + uint16_t chan13_raw; /*< [us] RC channel 13 value.*/ + uint16_t chan14_raw; /*< [us] RC channel 14 value.*/ + uint16_t chan15_raw; /*< [us] RC channel 15 value.*/ + uint16_t chan16_raw; /*< [us] RC channel 16 value.*/ + uint16_t chan17_raw; /*< [us] RC channel 17 value.*/ + uint16_t chan18_raw; /*< [us] RC channel 18 value.*/ + uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ + uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/ +} mavlink_rc_channels_t; #define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 #define MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN 42 @@ -44,6 +44,7 @@ typedef struct __mavlink_rc_channels_t { "RC_CHANNELS", \ 21, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ + { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ @@ -62,7 +63,6 @@ typedef struct __mavlink_rc_channels_t { { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ } \ } @@ -71,6 +71,7 @@ typedef struct __mavlink_rc_channels_t { "RC_CHANNELS", \ 21, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ + { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ @@ -89,7 +90,6 @@ typedef struct __mavlink_rc_channels_t { { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ } \ } @@ -101,27 +101,27 @@ typedef struct __mavlink_rc_channels_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw [us] RC channel 1 value. + * @param chan2_raw [us] RC channel 2 value. + * @param chan3_raw [us] RC channel 3 value. + * @param chan4_raw [us] RC channel 4 value. + * @param chan5_raw [us] RC channel 5 value. + * @param chan6_raw [us] RC channel 6 value. + * @param chan7_raw [us] RC channel 7 value. + * @param chan8_raw [us] RC channel 8 value. + * @param chan9_raw [us] RC channel 9 value. + * @param chan10_raw [us] RC channel 10 value. + * @param chan11_raw [us] RC channel 11 value. + * @param chan12_raw [us] RC channel 12 value. + * @param chan13_raw [us] RC channel 13 value. + * @param chan14_raw [us] RC channel 14 value. + * @param chan15_raw [us] RC channel 15 value. + * @param chan16_raw [us] RC channel 16 value. + * @param chan17_raw [us] RC channel 17 value. + * @param chan18_raw [us] RC channel 18 value. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -189,27 +189,27 @@ static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw [us] RC channel 1 value. + * @param chan2_raw [us] RC channel 2 value. + * @param chan3_raw [us] RC channel 3 value. + * @param chan4_raw [us] RC channel 4 value. + * @param chan5_raw [us] RC channel 5 value. + * @param chan6_raw [us] RC channel 6 value. + * @param chan7_raw [us] RC channel 7 value. + * @param chan8_raw [us] RC channel 8 value. + * @param chan9_raw [us] RC channel 9 value. + * @param chan10_raw [us] RC channel 10 value. + * @param chan11_raw [us] RC channel 11 value. + * @param chan12_raw [us] RC channel 12 value. + * @param chan13_raw [us] RC channel 13 value. + * @param chan14_raw [us] RC channel 14 value. + * @param chan15_raw [us] RC channel 15 value. + * @param chan16_raw [us] RC channel 16 value. + * @param chan17_raw [us] RC channel 17 value. + * @param chan18_raw [us] RC channel 18 value. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -303,27 +303,27 @@ static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, ui * @brief Send a rc_channels message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw [us] RC channel 1 value. + * @param chan2_raw [us] RC channel 2 value. + * @param chan3_raw [us] RC channel 3 value. + * @param chan4_raw [us] RC channel 4 value. + * @param chan5_raw [us] RC channel 5 value. + * @param chan6_raw [us] RC channel 6 value. + * @param chan7_raw [us] RC channel 7 value. + * @param chan8_raw [us] RC channel 8 value. + * @param chan9_raw [us] RC channel 9 value. + * @param chan10_raw [us] RC channel 10 value. + * @param chan11_raw [us] RC channel 11 value. + * @param chan12_raw [us] RC channel 12 value. + * @param chan13_raw [us] RC channel 13 value. + * @param chan14_raw [us] RC channel 14 value. + * @param chan15_raw [us] RC channel 15 value. + * @param chan16_raw [us] RC channel 16 value. + * @param chan17_raw [us] RC channel 17 value. + * @param chan18_raw [us] RC channel 18 value. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -468,7 +468,7 @@ static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field time_boot_ms from rc_channels message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) { @@ -478,7 +478,7 @@ static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_me /** * @brief Get field chancount from rc_channels message * - * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. */ static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) { @@ -488,7 +488,7 @@ static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_messag /** * @brief Get field chan1_raw from rc_channels message * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 1 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) { @@ -498,7 +498,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_messa /** * @brief Get field chan2_raw from rc_channels message * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 2 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) { @@ -508,7 +508,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_messa /** * @brief Get field chan3_raw from rc_channels message * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 3 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) { @@ -518,7 +518,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_messa /** * @brief Get field chan4_raw from rc_channels message * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 4 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) { @@ -528,7 +528,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_messa /** * @brief Get field chan5_raw from rc_channels message * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 5 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) { @@ -538,7 +538,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_messa /** * @brief Get field chan6_raw from rc_channels message * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 6 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) { @@ -548,7 +548,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_messa /** * @brief Get field chan7_raw from rc_channels message * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 7 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) { @@ -558,7 +558,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_messa /** * @brief Get field chan8_raw from rc_channels message * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 8 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) { @@ -568,7 +568,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_messa /** * @brief Get field chan9_raw from rc_channels message * - * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 9 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) { @@ -578,7 +578,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_messa /** * @brief Get field chan10_raw from rc_channels message * - * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 10 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) { @@ -588,7 +588,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_mess /** * @brief Get field chan11_raw from rc_channels message * - * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 11 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) { @@ -598,7 +598,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_mess /** * @brief Get field chan12_raw from rc_channels message * - * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 12 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) { @@ -608,7 +608,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_mess /** * @brief Get field chan13_raw from rc_channels message * - * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 13 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) { @@ -618,7 +618,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_mess /** * @brief Get field chan14_raw from rc_channels message * - * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 14 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) { @@ -628,7 +628,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_mess /** * @brief Get field chan15_raw from rc_channels message * - * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 15 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) { @@ -638,7 +638,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_mess /** * @brief Get field chan16_raw from rc_channels message * - * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 16 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) { @@ -648,7 +648,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_mess /** * @brief Get field chan17_raw from rc_channels message * - * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 17 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) { @@ -658,7 +658,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_mess /** * @brief Get field chan18_raw from rc_channels message * - * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 18 value. */ static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) { @@ -668,7 +668,7 @@ static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_mess /** * @brief Get field rssi from rc_channels message * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_rc_channels_override.h b/lib/main/MAVLink/common/mavlink_msg_rc_channels_override.h index 970e926935..b45c6ae85b 100755 --- a/lib/main/MAVLink/common/mavlink_msg_rc_channels_override.h +++ b/lib/main/MAVLink/common/mavlink_msg_rc_channels_override.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 -MAVPACKED( + typedef struct __mavlink_rc_channels_override_t { - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_rc_channels_override_t; + uint16_t chan1_raw; /*< [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan2_raw; /*< [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan3_raw; /*< [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan4_raw; /*< [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan5_raw; /*< [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan6_raw; /*< [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan7_raw; /*< [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan8_raw; /*< [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_rc_channels_override_t; #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN 18 @@ -32,7 +32,9 @@ typedef struct __mavlink_rc_channels_override_t { 70, \ "RC_CHANNELS_OVERRIDE", \ 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ @@ -40,15 +42,15 @@ typedef struct __mavlink_rc_channels_override_t { { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ "RC_CHANNELS_OVERRIDE", \ 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ @@ -56,8 +58,6 @@ typedef struct __mavlink_rc_channels_override_t { { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ } \ } #endif @@ -68,16 +68,16 @@ typedef struct __mavlink_rc_channels_override_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t syst * @brief Send a rc_channels_override message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t * /** * @brief Get field target_system from rc_channels_override message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const m /** * @brief Get field target_component from rc_channels_override message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(cons /** * @brief Get field chan1_raw from rc_channels_override message * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavl /** * @brief Get field chan2_raw from rc_channels_override message * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavl /** * @brief Get field chan3_raw from rc_channels_override message * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavl /** * @brief Get field chan4_raw from rc_channels_override message * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavl /** * @brief Get field chan5_raw from rc_channels_override message * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavl /** * @brief Get field chan6_raw from rc_channels_override message * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavl /** * @brief Get field chan7_raw from rc_channels_override message * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavl /** * @brief Get field chan8_raw from rc_channels_override message * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. */ static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_rc_channels_raw.h b/lib/main/MAVLink/common/mavlink_msg_rc_channels_raw.h index 87d1b4a82f..cbd7fd8428 100755 --- a/lib/main/MAVLink/common/mavlink_msg_rc_channels_raw.h +++ b/lib/main/MAVLink/common/mavlink_msg_rc_channels_raw.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 -MAVPACKED( + typedef struct __mavlink_rc_channels_raw_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_raw_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + uint16_t chan1_raw; /*< [us] RC channel 1 value.*/ + uint16_t chan2_raw; /*< [us] RC channel 2 value.*/ + uint16_t chan3_raw; /*< [us] RC channel 3 value.*/ + uint16_t chan4_raw; /*< [us] RC channel 4 value.*/ + uint16_t chan5_raw; /*< [us] RC channel 5 value.*/ + uint16_t chan6_raw; /*< [us] RC channel 6 value.*/ + uint16_t chan7_raw; /*< [us] RC channel 7 value.*/ + uint16_t chan8_raw; /*< [us] RC channel 8 value.*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.*/ + uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/ +} mavlink_rc_channels_raw_t; #define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 #define MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN 22 @@ -34,6 +34,7 @@ typedef struct __mavlink_rc_channels_raw_t { "RC_CHANNELS_RAW", \ 11, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ @@ -42,7 +43,6 @@ typedef struct __mavlink_rc_channels_raw_t { { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ } \ } @@ -51,6 +51,7 @@ typedef struct __mavlink_rc_channels_raw_t { "RC_CHANNELS_RAW", \ 11, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ @@ -59,7 +60,6 @@ typedef struct __mavlink_rc_channels_raw_t { { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ } \ } @@ -71,17 +71,17 @@ typedef struct __mavlink_rc_channels_raw_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param chan1_raw [us] RC channel 1 value. + * @param chan2_raw [us] RC channel 2 value. + * @param chan3_raw [us] RC channel 3 value. + * @param chan4_raw [us] RC channel 4 value. + * @param chan5_raw [us] RC channel 5 value. + * @param chan6_raw [us] RC channel 6 value. + * @param chan7_raw [us] RC channel 7 value. + * @param chan8_raw [us] RC channel 8 value. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -129,17 +129,17 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param chan1_raw [us] RC channel 1 value. + * @param chan2_raw [us] RC channel 2 value. + * @param chan3_raw [us] RC channel 3 value. + * @param chan4_raw [us] RC channel 4 value. + * @param chan5_raw [us] RC channel 5 value. + * @param chan6_raw [us] RC channel 6 value. + * @param chan7_raw [us] RC channel 7 value. + * @param chan8_raw [us] RC channel 8 value. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -213,17 +213,17 @@ static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id * @brief Send a rc_channels_raw message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param chan1_raw [us] RC channel 1 value. + * @param chan2_raw [us] RC channel 2 value. + * @param chan3_raw [us] RC channel 3 value. + * @param chan4_raw [us] RC channel 4 value. + * @param chan5_raw [us] RC channel 5 value. + * @param chan6_raw [us] RC channel 6 value. + * @param chan7_raw [us] RC channel 7 value. + * @param chan8_raw [us] RC channel 8 value. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -328,7 +328,7 @@ static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbu /** * @brief Get field time_boot_ms from rc_channels_raw message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) { @@ -338,7 +338,7 @@ static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlin /** * @brief Get field port from rc_channels_raw message * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @return Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. */ static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) { @@ -348,7 +348,7 @@ static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message /** * @brief Get field chan1_raw from rc_channels_raw message * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 1 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) { @@ -358,7 +358,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_m /** * @brief Get field chan2_raw from rc_channels_raw message * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 2 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) { @@ -368,7 +368,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_m /** * @brief Get field chan3_raw from rc_channels_raw message * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 3 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) { @@ -378,7 +378,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_m /** * @brief Get field chan4_raw from rc_channels_raw message * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 4 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) { @@ -388,7 +388,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_m /** * @brief Get field chan5_raw from rc_channels_raw message * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 5 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) { @@ -398,7 +398,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_m /** * @brief Get field chan6_raw from rc_channels_raw message * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 6 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_m /** * @brief Get field chan7_raw from rc_channels_raw message * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 7 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_m /** * @brief Get field chan8_raw from rc_channels_raw message * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @return [us] RC channel 8 value. */ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_m /** * @brief Get field rssi from rc_channels_raw message * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_rc_channels_scaled.h b/lib/main/MAVLink/common/mavlink_msg_rc_channels_scaled.h index 5b04333149..9d516d1ccc 100755 --- a/lib/main/MAVLink/common/mavlink_msg_rc_channels_scaled.h +++ b/lib/main/MAVLink/common/mavlink_msg_rc_channels_scaled.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 -MAVPACKED( + typedef struct __mavlink_rc_channels_scaled_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t chan1_scaled; /*< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan2_scaled; /*< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan3_scaled; /*< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan4_scaled; /*< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan5_scaled; /*< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan6_scaled; /*< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan7_scaled; /*< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan8_scaled; /*< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_scaled_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + int16_t chan1_scaled; /*< RC channel 1 value scaled.*/ + int16_t chan2_scaled; /*< RC channel 2 value scaled.*/ + int16_t chan3_scaled; /*< RC channel 3 value scaled.*/ + int16_t chan4_scaled; /*< RC channel 4 value scaled.*/ + int16_t chan5_scaled; /*< RC channel 5 value scaled.*/ + int16_t chan6_scaled; /*< RC channel 6 value scaled.*/ + int16_t chan7_scaled; /*< RC channel 7 value scaled.*/ + int16_t chan8_scaled; /*< RC channel 8 value scaled.*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.*/ + uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.*/ +} mavlink_rc_channels_scaled_t; #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN 22 @@ -34,6 +34,7 @@ typedef struct __mavlink_rc_channels_scaled_t { "RC_CHANNELS_SCALED", \ 11, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ @@ -42,7 +43,6 @@ typedef struct __mavlink_rc_channels_scaled_t { { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ } \ } @@ -51,6 +51,7 @@ typedef struct __mavlink_rc_channels_scaled_t { "RC_CHANNELS_SCALED", \ 11, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ @@ -59,7 +60,6 @@ typedef struct __mavlink_rc_channels_scaled_t { { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ } \ } @@ -71,17 +71,17 @@ typedef struct __mavlink_rc_channels_scaled_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param chan1_scaled RC channel 1 value scaled. + * @param chan2_scaled RC channel 2 value scaled. + * @param chan3_scaled RC channel 3 value scaled. + * @param chan4_scaled RC channel 4 value scaled. + * @param chan5_scaled RC channel 5 value scaled. + * @param chan6_scaled RC channel 6 value scaled. + * @param chan7_scaled RC channel 7 value scaled. + * @param chan8_scaled RC channel 8 value scaled. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -129,17 +129,17 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param chan1_scaled RC channel 1 value scaled. + * @param chan2_scaled RC channel 2 value scaled. + * @param chan3_scaled RC channel 3 value scaled. + * @param chan4_scaled RC channel 4 value scaled. + * @param chan5_scaled RC channel 5 value scaled. + * @param chan6_scaled RC channel 6 value scaled. + * @param chan7_scaled RC channel 7 value scaled. + * @param chan8_scaled RC channel 8 value scaled. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -213,17 +213,17 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system * @brief Send a rc_channels_scaled message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param chan1_scaled RC channel 1 value scaled. + * @param chan2_scaled RC channel 2 value scaled. + * @param chan3_scaled RC channel 3 value scaled. + * @param chan4_scaled RC channel 4 value scaled. + * @param chan5_scaled RC channel 5 value scaled. + * @param chan6_scaled RC channel 6 value scaled. + * @param chan7_scaled RC channel 7 value scaled. + * @param chan8_scaled RC channel 8 value scaled. + * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -328,7 +328,7 @@ static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *ms /** * @brief Get field time_boot_ms from rc_channels_scaled message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) { @@ -338,7 +338,7 @@ static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mav /** * @brief Get field port from rc_channels_scaled message * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @return Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. */ static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) { @@ -348,7 +348,7 @@ static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_mess /** * @brief Get field chan1_scaled from rc_channels_scaled message * - * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 1 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) { @@ -358,7 +358,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavl /** * @brief Get field chan2_scaled from rc_channels_scaled message * - * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 2 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) { @@ -368,7 +368,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavl /** * @brief Get field chan3_scaled from rc_channels_scaled message * - * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 3 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) { @@ -378,7 +378,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavl /** * @brief Get field chan4_scaled from rc_channels_scaled message * - * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 4 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) { @@ -388,7 +388,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavl /** * @brief Get field chan5_scaled from rc_channels_scaled message * - * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 5 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) { @@ -398,7 +398,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavl /** * @brief Get field chan6_scaled from rc_channels_scaled message * - * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 6 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavl /** * @brief Get field chan7_scaled from rc_channels_scaled message * - * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 7 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavl /** * @brief Get field chan8_scaled from rc_channels_scaled message * - * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @return RC channel 8 value scaled. */ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavl /** * @brief Get field rssi from rc_channels_scaled message * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. */ static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h b/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h index 047c2c342f..f1d739588e 100755 --- a/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h +++ b/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 -MAVPACKED( + typedef struct __mavlink_request_data_stream_t { - uint16_t req_message_rate; /*< The requested message rate*/ - uint8_t target_system; /*< The target requested to send the message stream.*/ - uint8_t target_component; /*< The target requested to send the message stream.*/ - uint8_t req_stream_id; /*< The ID of the requested data stream*/ - uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ -}) mavlink_request_data_stream_t; + uint16_t req_message_rate; /*< [Hz] The requested message rate*/ + uint8_t target_system; /*< The target requested to send the message stream.*/ + uint8_t target_component; /*< The target requested to send the message stream.*/ + uint8_t req_stream_id; /*< The ID of the requested data stream*/ + uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ +} mavlink_request_data_stream_t; #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN 6 @@ -27,10 +27,10 @@ typedef struct __mavlink_request_data_stream_t { 66, \ "REQUEST_DATA_STREAM", \ 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ } \ } @@ -38,10 +38,10 @@ typedef struct __mavlink_request_data_stream_t { #define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ "REQUEST_DATA_STREAM", \ 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ } \ } @@ -53,11 +53,11 @@ typedef struct __mavlink_request_data_stream_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate [Hz] The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -93,11 +93,11 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate [Hz] The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -159,11 +159,11 @@ static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t syste * @brief Send a request_data_stream message * @param chan MAVLink channel to send the message * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate [Hz] The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -244,7 +244,7 @@ static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *m /** * @brief Get field target_system from request_data_stream message * - * @return The target requested to send the message stream. + * @return The target requested to send the message stream. */ static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) { @@ -254,7 +254,7 @@ static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const ma /** * @brief Get field target_component from request_data_stream message * - * @return The target requested to send the message stream. + * @return The target requested to send the message stream. */ static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) { @@ -264,7 +264,7 @@ static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const /** * @brief Get field req_stream_id from request_data_stream message * - * @return The ID of the requested data stream + * @return The ID of the requested data stream */ static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) { @@ -274,7 +274,7 @@ static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const ma /** * @brief Get field req_message_rate from request_data_stream message * - * @return The requested message rate + * @return [Hz] The requested message rate */ static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) { @@ -284,7 +284,7 @@ static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(cons /** * @brief Get field start_stop from request_data_stream message * - * @return 1 to start sending, 0 to stop sending. + * @return 1 to start sending, 0 to stop sending. */ static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_resource_request.h b/lib/main/MAVLink/common/mavlink_msg_resource_request.h index 69a11771f3..a8ee9a6398 100755 --- a/lib/main/MAVLink/common/mavlink_msg_resource_request.h +++ b/lib/main/MAVLink/common/mavlink_msg_resource_request.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 -MAVPACKED( + typedef struct __mavlink_resource_request_t { - uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ - uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ - uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ - uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ - uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ -}) mavlink_resource_request_t; + uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ + uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ + uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ + uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ + uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ +} mavlink_resource_request_t; #define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN 243 @@ -54,11 +54,11 @@ typedef struct __mavlink_resource_request_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -92,11 +92,11 @@ static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -156,11 +156,11 @@ static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_i * @brief Send a resource_request message * @param chan MAVLink channel to send the message * - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -237,7 +237,7 @@ static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgb /** * @brief Get field request_id from resource_request message * - * @return Request ID. This ID should be re-used when sending back URI contents + * @return Request ID. This ID should be re-used when sending back URI contents */ static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg) { @@ -247,7 +247,7 @@ static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_ /** * @brief Get field uri_type from resource_request message * - * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary */ static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg) { @@ -257,7 +257,7 @@ static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_me /** * @brief Get field uri from resource_request message * - * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) */ static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri) { @@ -267,7 +267,7 @@ static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_messag /** * @brief Get field transfer_type from resource_request message * - * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. */ static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg) { @@ -277,7 +277,7 @@ static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavli /** * @brief Get field storage from resource_request message * - * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). */ static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage) { diff --git a/lib/main/MAVLink/common/mavlink_msg_safety_allowed_area.h b/lib/main/MAVLink/common/mavlink_msg_safety_allowed_area.h index cad1c198e4..bad669a0cb 100755 --- a/lib/main/MAVLink/common/mavlink_msg_safety_allowed_area.h +++ b/lib/main/MAVLink/common/mavlink_msg_safety_allowed_area.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 -MAVPACKED( + typedef struct __mavlink_safety_allowed_area_t { - float p1x; /*< x position 1 / Latitude 1*/ - float p1y; /*< y position 1 / Longitude 1*/ - float p1z; /*< z position 1 / Altitude 1*/ - float p2x; /*< x position 2 / Latitude 2*/ - float p2y; /*< y position 2 / Longitude 2*/ - float p2z; /*< z position 2 / Altitude 2*/ - uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -}) mavlink_safety_allowed_area_t; + float p1x; /*< [m] x position 1 / Latitude 1*/ + float p1y; /*< [m] y position 1 / Longitude 1*/ + float p1z; /*< [m] z position 1 / Altitude 1*/ + float p2x; /*< [m] x position 2 / Latitude 2*/ + float p2y; /*< [m] y position 2 / Longitude 2*/ + float p2z; /*< [m] z position 2 / Altitude 2*/ + uint8_t frame; /*< Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ +} mavlink_safety_allowed_area_t; #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN 25 @@ -29,26 +29,26 @@ typedef struct __mavlink_safety_allowed_area_t { 55, \ "SAFETY_ALLOWED_AREA", \ 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ "SAFETY_ALLOWED_AREA", \ 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ } \ } #endif @@ -59,13 +59,13 @@ typedef struct __mavlink_safety_allowed_area_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 + * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x [m] x position 1 / Latitude 1 + * @param p1y [m] y position 1 / Longitude 1 + * @param p1z [m] z position 1 / Altitude 1 + * @param p2x [m] x position 2 / Latitude 2 + * @param p2y [m] y position 2 / Longitude 2 + * @param p2z [m] z position 2 / Altitude 2 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 + * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x [m] x position 1 / Latitude 1 + * @param p1y [m] y position 1 / Longitude 1 + * @param p1z [m] z position 1 / Altitude 1 + * @param p2x [m] x position 2 / Latitude 2 + * @param p2y [m] y position 2 / Longitude 2 + * @param p2z [m] z position 2 / Altitude 2 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t syste * @brief Send a safety_allowed_area message * @param chan MAVLink channel to send the message * - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 + * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x [m] x position 1 / Latitude 1 + * @param p1y [m] y position 1 / Longitude 1 + * @param p1z [m] z position 1 / Altitude 1 + * @param p2x [m] x position 2 / Latitude 2 + * @param p2y [m] y position 2 / Longitude 2 + * @param p2z [m] z position 2 / Altitude 2 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *m /** * @brief Get field frame from safety_allowed_area message * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @return Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. */ static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_me /** * @brief Get field p1x from safety_allowed_area message * - * @return x position 1 / Latitude 1 + * @return [m] x position 1 / Latitude 1 */ static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_messag /** * @brief Get field p1y from safety_allowed_area message * - * @return y position 1 / Longitude 1 + * @return [m] y position 1 / Longitude 1 */ static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_messag /** * @brief Get field p1z from safety_allowed_area message * - * @return z position 1 / Altitude 1 + * @return [m] z position 1 / Altitude 1 */ static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_messag /** * @brief Get field p2x from safety_allowed_area message * - * @return x position 2 / Latitude 2 + * @return [m] x position 2 / Latitude 2 */ static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_messag /** * @brief Get field p2y from safety_allowed_area message * - * @return y position 2 / Longitude 2 + * @return [m] y position 2 / Longitude 2 */ static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_messag /** * @brief Get field p2z from safety_allowed_area message * - * @return z position 2 / Altitude 2 + * @return [m] z position 2 / Altitude 2 */ static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_safety_set_allowed_area.h b/lib/main/MAVLink/common/mavlink_msg_safety_set_allowed_area.h index 293c1f002a..eca9b274f7 100755 --- a/lib/main/MAVLink/common/mavlink_msg_safety_set_allowed_area.h +++ b/lib/main/MAVLink/common/mavlink_msg_safety_set_allowed_area.h @@ -3,18 +3,18 @@ #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 -MAVPACKED( + typedef struct __mavlink_safety_set_allowed_area_t { - float p1x; /*< x position 1 / Latitude 1*/ - float p1y; /*< y position 1 / Longitude 1*/ - float p1z; /*< z position 1 / Altitude 1*/ - float p2x; /*< x position 2 / Latitude 2*/ - float p2y; /*< y position 2 / Longitude 2*/ - float p2z; /*< z position 2 / Altitude 2*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -}) mavlink_safety_set_allowed_area_t; + float p1x; /*< [m] x position 1 / Latitude 1*/ + float p1y; /*< [m] y position 1 / Longitude 1*/ + float p1z; /*< [m] z position 1 / Altitude 1*/ + float p2x; /*< [m] x position 2 / Latitude 2*/ + float p2y; /*< [m] y position 2 / Longitude 2*/ + float p2z; /*< [m] z position 2 / Altitude 2*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ +} mavlink_safety_set_allowed_area_t; #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN 27 @@ -31,30 +31,30 @@ typedef struct __mavlink_safety_set_allowed_area_t { 54, \ "SAFETY_SET_ALLOWED_AREA", \ 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ "SAFETY_SET_ALLOWED_AREA", \ 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ } \ } #endif @@ -65,15 +65,15 @@ typedef struct __mavlink_safety_set_allowed_area_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x [m] x position 1 / Latitude 1 + * @param p1y [m] y position 1 / Longitude 1 + * @param p1z [m] z position 1 / Altitude 1 + * @param p2x [m] x position 2 / Latitude 2 + * @param p2y [m] y position 2 / Longitude 2 + * @param p2z [m] z position 2 / Altitude 2 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -117,15 +117,15 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x [m] x position 1 / Latitude 1 + * @param p1y [m] y position 1 / Longitude 1 + * @param p1z [m] z position 1 / Altitude 1 + * @param p2x [m] x position 2 / Latitude 2 + * @param p2y [m] y position 2 / Longitude 2 + * @param p2z [m] z position 2 / Altitude 2 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -195,15 +195,15 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t s * @brief Send a safety_set_allowed_area message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x [m] x position 1 / Latitude 1 + * @param p1y [m] y position 1 / Longitude 1 + * @param p1z [m] z position 1 / Altitude 1 + * @param p2x [m] x position 2 / Latitude 2 + * @param p2y [m] y position 2 / Longitude 2 + * @param p2z [m] z position 2 / Altitude 2 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -300,7 +300,7 @@ static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_ /** * @brief Get field target_system from safety_set_allowed_area message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) { @@ -310,7 +310,7 @@ static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(cons /** * @brief Get field target_component from safety_set_allowed_area message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) { @@ -320,7 +320,7 @@ static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(c /** * @brief Get field frame from safety_set_allowed_area message * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @return Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. */ static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) { @@ -330,7 +330,7 @@ static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlin /** * @brief Get field p1x from safety_set_allowed_area message * - * @return x position 1 / Latitude 1 + * @return [m] x position 1 / Latitude 1 */ static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) { @@ -340,7 +340,7 @@ static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_me /** * @brief Get field p1y from safety_set_allowed_area message * - * @return y position 1 / Longitude 1 + * @return [m] y position 1 / Longitude 1 */ static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) { @@ -350,7 +350,7 @@ static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_me /** * @brief Get field p1z from safety_set_allowed_area message * - * @return z position 1 / Altitude 1 + * @return [m] z position 1 / Altitude 1 */ static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) { @@ -360,7 +360,7 @@ static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_me /** * @brief Get field p2x from safety_set_allowed_area message * - * @return x position 2 / Latitude 2 + * @return [m] x position 2 / Latitude 2 */ static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) { @@ -370,7 +370,7 @@ static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_me /** * @brief Get field p2y from safety_set_allowed_area message * - * @return y position 2 / Longitude 2 + * @return [m] y position 2 / Longitude 2 */ static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_me /** * @brief Get field p2z from safety_set_allowed_area message * - * @return z position 2 / Altitude 2 + * @return [m] z position 2 / Altitude 2 */ static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_scaled_imu.h b/lib/main/MAVLink/common/mavlink_msg_scaled_imu.h index 2994d999a5..f94b146bf2 100755 --- a/lib/main/MAVLink/common/mavlink_msg_scaled_imu.h +++ b/lib/main/MAVLink/common/mavlink_msg_scaled_imu.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_SCALED_IMU 26 -MAVPACKED( + typedef struct __mavlink_scaled_imu_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + int16_t xacc; /*< [mG] X acceleration*/ + int16_t yacc; /*< [mG] Y acceleration*/ + int16_t zacc; /*< [mG] Z acceleration*/ + int16_t xgyro; /*< [mrad/s] Angular speed around X axis*/ + int16_t ygyro; /*< [mrad/s] Angular speed around Y axis*/ + int16_t zgyro; /*< [mrad/s] Angular speed around Z axis*/ + int16_t xmag; /*< [mgauss] X Magnetic field*/ + int16_t ymag; /*< [mgauss] Y Magnetic field*/ + int16_t zmag; /*< [mgauss] Z Magnetic field*/ +} mavlink_scaled_imu_t; #define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 #define MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN 22 @@ -68,16 +68,16 @@ typedef struct __mavlink_scaled_imu_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uin * @brief Send a scaled_imu message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field time_boot_ms from scaled_imu message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_mes /** * @brief Get field xacc from scaled_imu message * - * @return X acceleration (mg) + * @return [mG] X acceleration */ static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* m /** * @brief Get field yacc from scaled_imu message * - * @return Y acceleration (mg) + * @return [mG] Y acceleration */ static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* m /** * @brief Get field zacc from scaled_imu message * - * @return Z acceleration (mg) + * @return [mG] Z acceleration */ static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* m /** * @brief Get field xgyro from scaled_imu message * - * @return Angular speed around X axis (millirad /sec) + * @return [mrad/s] Angular speed around X axis */ static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* /** * @brief Get field ygyro from scaled_imu message * - * @return Angular speed around Y axis (millirad /sec) + * @return [mrad/s] Angular speed around Y axis */ static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* /** * @brief Get field zgyro from scaled_imu message * - * @return Angular speed around Z axis (millirad /sec) + * @return [mrad/s] Angular speed around Z axis */ static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* /** * @brief Get field xmag from scaled_imu message * - * @return X Magnetic field (milli tesla) + * @return [mgauss] X Magnetic field */ static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* m /** * @brief Get field ymag from scaled_imu message * - * @return Y Magnetic field (milli tesla) + * @return [mgauss] Y Magnetic field */ static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* m /** * @brief Get field zmag from scaled_imu message * - * @return Z Magnetic field (milli tesla) + * @return [mgauss] Z Magnetic field */ static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_scaled_imu2.h b/lib/main/MAVLink/common/mavlink_msg_scaled_imu2.h index c232691790..297874cb4a 100755 --- a/lib/main/MAVLink/common/mavlink_msg_scaled_imu2.h +++ b/lib/main/MAVLink/common/mavlink_msg_scaled_imu2.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_SCALED_IMU2 116 -MAVPACKED( + typedef struct __mavlink_scaled_imu2_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu2_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + int16_t xacc; /*< [mG] X acceleration*/ + int16_t yacc; /*< [mG] Y acceleration*/ + int16_t zacc; /*< [mG] Z acceleration*/ + int16_t xgyro; /*< [mrad/s] Angular speed around X axis*/ + int16_t ygyro; /*< [mrad/s] Angular speed around Y axis*/ + int16_t zgyro; /*< [mrad/s] Angular speed around Z axis*/ + int16_t xmag; /*< [mgauss] X Magnetic field*/ + int16_t ymag; /*< [mgauss] Y Magnetic field*/ + int16_t zmag; /*< [mgauss] Z Magnetic field*/ +} mavlink_scaled_imu2_t; #define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 #define MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN 22 @@ -68,16 +68,16 @@ typedef struct __mavlink_scaled_imu2_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, ui * @brief Send a scaled_imu2 message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field time_boot_ms from scaled_imu2 message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_me /** * @brief Get field xacc from scaled_imu2 message * - * @return X acceleration (mg) + * @return [mG] X acceleration */ static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* /** * @brief Get field yacc from scaled_imu2 message * - * @return Y acceleration (mg) + * @return [mG] Y acceleration */ static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* /** * @brief Get field zacc from scaled_imu2 message * - * @return Z acceleration (mg) + * @return [mG] Z acceleration */ static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* /** * @brief Get field xgyro from scaled_imu2 message * - * @return Angular speed around X axis (millirad /sec) + * @return [mrad/s] Angular speed around X axis */ static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* /** * @brief Get field ygyro from scaled_imu2 message * - * @return Angular speed around Y axis (millirad /sec) + * @return [mrad/s] Angular speed around Y axis */ static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* /** * @brief Get field zgyro from scaled_imu2 message * - * @return Angular speed around Z axis (millirad /sec) + * @return [mrad/s] Angular speed around Z axis */ static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* /** * @brief Get field xmag from scaled_imu2 message * - * @return X Magnetic field (milli tesla) + * @return [mgauss] X Magnetic field */ static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* /** * @brief Get field ymag from scaled_imu2 message * - * @return Y Magnetic field (milli tesla) + * @return [mgauss] Y Magnetic field */ static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* /** * @brief Get field zmag from scaled_imu2 message * - * @return Z Magnetic field (milli tesla) + * @return [mgauss] Z Magnetic field */ static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_scaled_imu3.h b/lib/main/MAVLink/common/mavlink_msg_scaled_imu3.h index 22b9d86cf0..d01ac948fd 100755 --- a/lib/main/MAVLink/common/mavlink_msg_scaled_imu3.h +++ b/lib/main/MAVLink/common/mavlink_msg_scaled_imu3.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_SCALED_IMU3 129 -MAVPACKED( + typedef struct __mavlink_scaled_imu3_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu3_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + int16_t xacc; /*< [mG] X acceleration*/ + int16_t yacc; /*< [mG] Y acceleration*/ + int16_t zacc; /*< [mG] Z acceleration*/ + int16_t xgyro; /*< [mrad/s] Angular speed around X axis*/ + int16_t ygyro; /*< [mrad/s] Angular speed around Y axis*/ + int16_t zgyro; /*< [mrad/s] Angular speed around Z axis*/ + int16_t xmag; /*< [mgauss] X Magnetic field*/ + int16_t ymag; /*< [mgauss] Y Magnetic field*/ + int16_t zmag; /*< [mgauss] Z Magnetic field*/ +} mavlink_scaled_imu3_t; #define MAVLINK_MSG_ID_SCALED_IMU3_LEN 22 #define MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN 22 @@ -68,16 +68,16 @@ typedef struct __mavlink_scaled_imu3_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_imu3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, ui * @brief Send a scaled_imu3 message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param xacc [mG] X acceleration + * @param yacc [mG] Y acceleration + * @param zacc [mG] Z acceleration + * @param xgyro [mrad/s] Angular speed around X axis + * @param ygyro [mrad/s] Angular speed around Y axis + * @param zgyro [mrad/s] Angular speed around Z axis + * @param xmag [mgauss] X Magnetic field + * @param ymag [mgauss] Y Magnetic field + * @param zmag [mgauss] Z Magnetic field */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field time_boot_ms from scaled_imu3 message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_me /** * @brief Get field xacc from scaled_imu3 message * - * @return X acceleration (mg) + * @return [mG] X acceleration */ static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* /** * @brief Get field yacc from scaled_imu3 message * - * @return Y acceleration (mg) + * @return [mG] Y acceleration */ static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* /** * @brief Get field zacc from scaled_imu3 message * - * @return Z acceleration (mg) + * @return [mG] Z acceleration */ static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* /** * @brief Get field xgyro from scaled_imu3 message * - * @return Angular speed around X axis (millirad /sec) + * @return [mrad/s] Angular speed around X axis */ static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* /** * @brief Get field ygyro from scaled_imu3 message * - * @return Angular speed around Y axis (millirad /sec) + * @return [mrad/s] Angular speed around Y axis */ static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* /** * @brief Get field zgyro from scaled_imu3 message * - * @return Angular speed around Z axis (millirad /sec) + * @return [mrad/s] Angular speed around Z axis */ static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* /** * @brief Get field xmag from scaled_imu3 message * - * @return X Magnetic field (milli tesla) + * @return [mgauss] X Magnetic field */ static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* /** * @brief Get field ymag from scaled_imu3 message * - * @return Y Magnetic field (milli tesla) + * @return [mgauss] Y Magnetic field */ static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* /** * @brief Get field zmag from scaled_imu3 message * - * @return Z Magnetic field (milli tesla) + * @return [mgauss] Z Magnetic field */ static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_scaled_pressure.h b/lib/main/MAVLink/common/mavlink_msg_scaled_pressure.h index 0dcfc9277d..9889c4676a 100755 --- a/lib/main/MAVLink/common/mavlink_msg_scaled_pressure.h +++ b/lib/main/MAVLink/common/mavlink_msg_scaled_pressure.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_SCALED_PRESSURE 29 -MAVPACKED( + typedef struct __mavlink_scaled_pressure_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float press_abs; /*< [hPa] Absolute pressure*/ + float press_diff; /*< [hPa] Differential pressure 1*/ + int16_t temperature; /*< [cdegC] Absolute pressure temperature*/ +} mavlink_scaled_pressure_t; #define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 #define MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN 14 @@ -50,10 +50,10 @@ typedef struct __mavlink_scaled_pressure_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure 1 + * @param temperature [cdegC] Absolute pressure temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure 1 + * @param temperature [cdegC] Absolute pressure temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id * @brief Send a scaled_pressure message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure 1 + * @param temperature [cdegC] Absolute pressure temperature */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbu /** * @brief Get field time_boot_ms from scaled_pressure message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlin /** * @brief Get field press_abs from scaled_pressure message * - * @return Absolute pressure (hectopascal) + * @return [hPa] Absolute pressure */ static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_mess /** * @brief Get field press_diff from scaled_pressure message * - * @return Differential pressure 1 (hectopascal) + * @return [hPa] Differential pressure 1 */ static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_mes /** * @brief Get field temperature from scaled_pressure message * - * @return Temperature measurement (0.01 degrees celsius) + * @return [cdegC] Absolute pressure temperature */ static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_scaled_pressure2.h b/lib/main/MAVLink/common/mavlink_msg_scaled_pressure2.h index 1e7920b040..7ac74c6758 100755 --- a/lib/main/MAVLink/common/mavlink_msg_scaled_pressure2.h +++ b/lib/main/MAVLink/common/mavlink_msg_scaled_pressure2.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_SCALED_PRESSURE2 137 -MAVPACKED( + typedef struct __mavlink_scaled_pressure2_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure2_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float press_abs; /*< [hPa] Absolute pressure*/ + float press_diff; /*< [hPa] Differential pressure*/ + int16_t temperature; /*< [cdegC] Absolute pressure temperature*/ +} mavlink_scaled_pressure2_t; #define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 14 #define MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN 14 @@ -50,10 +50,10 @@ typedef struct __mavlink_scaled_pressure2_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure + * @param temperature [cdegC] Absolute pressure temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure + * @param temperature [cdegC] Absolute pressure temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_i * @brief Send a scaled_pressure2 message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure + * @param temperature [cdegC] Absolute pressure temperature */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgb /** * @brief Get field time_boot_ms from scaled_pressure2 message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavli /** * @brief Get field press_abs from scaled_pressure2 message * - * @return Absolute pressure (hectopascal) + * @return [hPa] Absolute pressure */ static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_mes /** * @brief Get field press_diff from scaled_pressure2 message * - * @return Differential pressure 1 (hectopascal) + * @return [hPa] Differential pressure */ static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_me /** * @brief Get field temperature from scaled_pressure2 message * - * @return Temperature measurement (0.01 degrees celsius) + * @return [cdegC] Absolute pressure temperature */ static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_scaled_pressure3.h b/lib/main/MAVLink/common/mavlink_msg_scaled_pressure3.h index a0b6586e90..e0007cf8ed 100755 --- a/lib/main/MAVLink/common/mavlink_msg_scaled_pressure3.h +++ b/lib/main/MAVLink/common/mavlink_msg_scaled_pressure3.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_SCALED_PRESSURE3 143 -MAVPACKED( + typedef struct __mavlink_scaled_pressure3_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure3_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float press_abs; /*< [hPa] Absolute pressure*/ + float press_diff; /*< [hPa] Differential pressure*/ + int16_t temperature; /*< [cdegC] Absolute pressure temperature*/ +} mavlink_scaled_pressure3_t; #define MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN 14 #define MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN 14 @@ -50,10 +50,10 @@ typedef struct __mavlink_scaled_pressure3_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure + * @param temperature [cdegC] Absolute pressure temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure + * @param temperature [cdegC] Absolute pressure temperature * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_scaled_pressure3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_scaled_pressure3_encode_chan(uint8_t system_i * @brief Send a scaled_pressure3 message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param press_abs [hPa] Absolute pressure + * @param press_diff [hPa] Differential pressure + * @param temperature [cdegC] Absolute pressure temperature */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_scaled_pressure3_send_buf(mavlink_message_t *msgb /** * @brief Get field time_boot_ms from scaled_pressure3 message * - * @return Timestamp (milliseconds since system boot) + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavli /** * @brief Get field press_abs from scaled_pressure3 message * - * @return Absolute pressure (hectopascal) + * @return [hPa] Absolute pressure */ static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_mes /** * @brief Get field press_diff from scaled_pressure3 message * - * @return Differential pressure 1 (hectopascal) + * @return [hPa] Differential pressure */ static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_me /** * @brief Get field temperature from scaled_pressure3 message * - * @return Temperature measurement (0.01 degrees celsius) + * @return [cdegC] Absolute pressure temperature */ static inline int16_t mavlink_msg_scaled_pressure3_get_temperature(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_serial_control.h b/lib/main/MAVLink/common/mavlink_msg_serial_control.h index ce9581185a..16ed754cf6 100755 --- a/lib/main/MAVLink/common/mavlink_msg_serial_control.h +++ b/lib/main/MAVLink/common/mavlink_msg_serial_control.h @@ -3,15 +3,15 @@ #define MAVLINK_MSG_ID_SERIAL_CONTROL 126 -MAVPACKED( + typedef struct __mavlink_serial_control_t { - uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/ - uint16_t timeout; /*< Timeout for reply data in milliseconds*/ - uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/ - uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/ - uint8_t count; /*< how many bytes in this transfer*/ - uint8_t data[70]; /*< serial data*/ -}) mavlink_serial_control_t; + uint32_t baudrate; /*< [bits/s] Baudrate of transfer. Zero means no change.*/ + uint16_t timeout; /*< [ms] Timeout for reply data*/ + uint8_t device; /*< Serial control device type.*/ + uint8_t flags; /*< Bitmap of serial control flags.*/ + uint8_t count; /*< [bytes] how many bytes in this transfer*/ + uint8_t data[70]; /*< serial data*/ +} mavlink_serial_control_t; #define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 #define MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN 79 @@ -28,10 +28,10 @@ typedef struct __mavlink_serial_control_t { 126, \ "SERIAL_CONTROL", \ 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ + { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ + { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ } \ @@ -40,10 +40,10 @@ typedef struct __mavlink_serial_control_t { #define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ "SERIAL_CONTROL", \ 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ + { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ + { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ } \ @@ -56,12 +56,12 @@ typedef struct __mavlink_serial_control_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data + * @param device Serial control device type. + * @param flags Bitmap of serial control flags. + * @param timeout [ms] Timeout for reply data + * @param baudrate [bits/s] Baudrate of transfer. Zero means no change. + * @param count [bytes] how many bytes in this transfer + * @param data serial data * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -97,12 +97,12 @@ static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data + * @param device Serial control device type. + * @param flags Bitmap of serial control flags. + * @param timeout [ms] Timeout for reply data + * @param baudrate [bits/s] Baudrate of transfer. Zero means no change. + * @param count [bytes] how many bytes in this transfer + * @param data serial data * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -164,12 +164,12 @@ static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, * @brief Send a serial_control message * @param chan MAVLink channel to send the message * - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data + * @param device Serial control device type. + * @param flags Bitmap of serial control flags. + * @param timeout [ms] Timeout for reply data + * @param baudrate [bits/s] Baudrate of transfer. Zero means no change. + * @param count [bytes] how many bytes in this transfer + * @param data serial data */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -250,7 +250,7 @@ static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf /** * @brief Get field device from serial_control message * - * @return See SERIAL_CONTROL_DEV enum + * @return Serial control device type. */ static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_messag /** * @brief Get field flags from serial_control message * - * @return See SERIAL_CONTROL_FLAG enum + * @return Bitmap of serial control flags. */ static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) { @@ -270,7 +270,7 @@ static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message /** * @brief Get field timeout from serial_control message * - * @return Timeout for reply data in milliseconds + * @return [ms] Timeout for reply data */ static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) { @@ -280,7 +280,7 @@ static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_mess /** * @brief Get field baudrate from serial_control message * - * @return Baudrate of transfer. Zero means no change. + * @return [bits/s] Baudrate of transfer. Zero means no change. */ static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) { @@ -290,7 +290,7 @@ static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_mes /** * @brief Get field count from serial_control message * - * @return how many bytes in this transfer + * @return [bytes] how many bytes in this transfer */ static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) { @@ -300,7 +300,7 @@ static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message /** * @brief Get field data from serial_control message * - * @return serial data + * @return serial data */ static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) { diff --git a/lib/main/MAVLink/common/mavlink_msg_servo_output_raw.h b/lib/main/MAVLink/common/mavlink_msg_servo_output_raw.h index 0bf3936cdc..840c6a25f6 100755 --- a/lib/main/MAVLink/common/mavlink_msg_servo_output_raw.h +++ b/lib/main/MAVLink/common/mavlink_msg_servo_output_raw.h @@ -3,19 +3,19 @@ #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 -MAVPACKED( + typedef struct __mavlink_servo_output_raw_t { - uint32_t time_usec; /*< Timestamp (microseconds since system boot)*/ - uint16_t servo1_raw; /*< Servo output 1 value, in microseconds*/ - uint16_t servo2_raw; /*< Servo output 2 value, in microseconds*/ - uint16_t servo3_raw; /*< Servo output 3 value, in microseconds*/ - uint16_t servo4_raw; /*< Servo output 4 value, in microseconds*/ - uint16_t servo5_raw; /*< Servo output 5 value, in microseconds*/ - uint16_t servo6_raw; /*< Servo output 6 value, in microseconds*/ - uint16_t servo7_raw; /*< Servo output 7 value, in microseconds*/ - uint16_t servo8_raw; /*< Servo output 8 value, in microseconds*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.*/ -}) mavlink_servo_output_raw_t; + uint32_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + uint16_t servo1_raw; /*< [us] Servo output 1 value*/ + uint16_t servo2_raw; /*< [us] Servo output 2 value*/ + uint16_t servo3_raw; /*< [us] Servo output 3 value*/ + uint16_t servo4_raw; /*< [us] Servo output 4 value*/ + uint16_t servo5_raw; /*< [us] Servo output 5 value*/ + uint16_t servo6_raw; /*< [us] Servo output 6 value*/ + uint16_t servo7_raw; /*< [us] Servo output 7 value*/ + uint16_t servo8_raw; /*< [us] Servo output 8 value*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.*/ +} mavlink_servo_output_raw_t; #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN 21 @@ -33,6 +33,7 @@ typedef struct __mavlink_servo_output_raw_t { "SERVO_OUTPUT_RAW", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ @@ -41,7 +42,6 @@ typedef struct __mavlink_servo_output_raw_t { { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ } \ } #else @@ -49,6 +49,7 @@ typedef struct __mavlink_servo_output_raw_t { "SERVO_OUTPUT_RAW", \ 10, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ @@ -57,7 +58,6 @@ typedef struct __mavlink_servo_output_raw_t { { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ } \ } #endif @@ -68,16 +68,16 @@ typedef struct __mavlink_servo_output_raw_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param servo1_raw [us] Servo output 1 value + * @param servo2_raw [us] Servo output 2 value + * @param servo3_raw [us] Servo output 3 value + * @param servo4_raw [us] Servo output 4 value + * @param servo5_raw [us] Servo output 5 value + * @param servo6_raw [us] Servo output 6 value + * @param servo7_raw [us] Servo output 7 value + * @param servo8_raw [us] Servo output 8 value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -123,16 +123,16 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param servo1_raw [us] Servo output 1 value + * @param servo2_raw [us] Servo output 2 value + * @param servo3_raw [us] Servo output 3 value + * @param servo4_raw [us] Servo output 4 value + * @param servo5_raw [us] Servo output 5 value + * @param servo6_raw [us] Servo output 6 value + * @param servo7_raw [us] Servo output 7 value + * @param servo8_raw [us] Servo output 8 value * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -204,16 +204,16 @@ static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_i * @brief Send a servo_output_raw message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + * @param servo1_raw [us] Servo output 1 value + * @param servo2_raw [us] Servo output 2 value + * @param servo3_raw [us] Servo output 3 value + * @param servo4_raw [us] Servo output 4 value + * @param servo5_raw [us] Servo output 5 value + * @param servo6_raw [us] Servo output 6 value + * @param servo7_raw [us] Servo output 7 value + * @param servo8_raw [us] Servo output 8 value */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -314,7 +314,7 @@ static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgb /** * @brief Get field time_usec from servo_output_raw message * - * @return Timestamp (microseconds since system boot) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) { @@ -324,7 +324,7 @@ static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_ /** * @brief Get field port from servo_output_raw message * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @return Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. */ static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) { @@ -334,7 +334,7 @@ static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_messag /** * @brief Get field servo1_raw from servo_output_raw message * - * @return Servo output 1 value, in microseconds + * @return [us] Servo output 1 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) { @@ -344,7 +344,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink /** * @brief Get field servo2_raw from servo_output_raw message * - * @return Servo output 2 value, in microseconds + * @return [us] Servo output 2 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) { @@ -354,7 +354,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink /** * @brief Get field servo3_raw from servo_output_raw message * - * @return Servo output 3 value, in microseconds + * @return [us] Servo output 3 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) { @@ -364,7 +364,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink /** * @brief Get field servo4_raw from servo_output_raw message * - * @return Servo output 4 value, in microseconds + * @return [us] Servo output 4 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) { @@ -374,7 +374,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink /** * @brief Get field servo5_raw from servo_output_raw message * - * @return Servo output 5 value, in microseconds + * @return [us] Servo output 5 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) { @@ -384,7 +384,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink /** * @brief Get field servo6_raw from servo_output_raw message * - * @return Servo output 6 value, in microseconds + * @return [us] Servo output 6 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) { @@ -394,7 +394,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink /** * @brief Get field servo7_raw from servo_output_raw message * - * @return Servo output 7 value, in microseconds + * @return [us] Servo output 7 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) { @@ -404,7 +404,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink /** * @brief Get field servo8_raw from servo_output_raw message * - * @return Servo output 8 value, in microseconds + * @return [us] Servo output 8 value */ static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_actuator_control_target.h b/lib/main/MAVLink/common/mavlink_msg_set_actuator_control_target.h index f804d4bc85..7d21dac9d3 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_actuator_control_target.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_actuator_control_target.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139 -MAVPACKED( + typedef struct __mavlink_set_actuator_control_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_set_actuator_control_target_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ + uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_set_actuator_control_target_t; #define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43 #define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN 43 @@ -28,10 +28,10 @@ typedef struct __mavlink_set_actuator_control_target_t { "SET_ACTUATOR_CONTROL_TARGET", \ 5, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ } \ } #else @@ -39,10 +39,10 @@ typedef struct __mavlink_set_actuator_control_target_t { "SET_ACTUATOR_CONTROL_TARGET", \ 5, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ } \ } #endif @@ -53,11 +53,11 @@ typedef struct __mavlink_set_actuator_control_target_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t syst * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8 * @brief Send a set_actuator_control_target message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_mess /** * @brief Get field time_usec from set_actuator_control_target message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg) { @@ -246,7 +246,7 @@ static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(con /** * @brief Get field group_mlx from set_actuator_control_target message * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. */ static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) { @@ -256,7 +256,7 @@ static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(cons /** * @brief Get field target_system from set_actuator_control_target message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg) { @@ -266,7 +266,7 @@ static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system( /** * @brief Get field target_component from set_actuator_control_target message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_compone /** * @brief Get field controls from set_actuator_control_target message * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. */ static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h b/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h index 1b68caa025..94a2e856b8 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h @@ -3,18 +3,18 @@ #define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 -MAVPACKED( + typedef struct __mavlink_set_attitude_target_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< Body roll rate in radians per second*/ - float body_pitch_rate; /*< Body roll rate in radians per second*/ - float body_yaw_rate; /*< Body roll rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude*/ -}) mavlink_set_attitude_target_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float body_roll_rate; /*< [rad/s] Body roll rate*/ + float body_pitch_rate; /*< [rad/s] Body pitch rate*/ + float body_yaw_rate; /*< [rad/s] Body yaw rate*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude*/ +} mavlink_set_attitude_target_t; #define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 #define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN 39 @@ -32,14 +32,14 @@ typedef struct __mavlink_set_attitude_target_t { "SET_ATTITUDE_TARGET", \ 9, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ } \ } #else @@ -47,14 +47,14 @@ typedef struct __mavlink_set_attitude_target_t { "SET_ATTITUDE_TARGET", \ 9, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ } \ } #endif @@ -65,15 +65,15 @@ typedef struct __mavlink_set_attitude_target_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate [rad/s] Body roll rate + * @param body_pitch_rate [rad/s] Body pitch rate + * @param body_yaw_rate [rad/s] Body yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -115,15 +115,15 @@ static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, u * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate [rad/s] Body roll rate + * @param body_pitch_rate [rad/s] Body pitch rate + * @param body_yaw_rate [rad/s] Body yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -191,15 +191,15 @@ static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t syste * @brief Send a set_attitude_target message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate [rad/s] Body roll rate + * @param body_pitch_rate [rad/s] Body pitch rate + * @param body_yaw_rate [rad/s] Body yaw rate + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -292,7 +292,7 @@ static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *m /** * @brief Get field time_boot_ms from set_attitude_target message * - * @return Timestamp in milliseconds since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const ma /** * @brief Get field target_system from set_attitude_target message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const ma /** * @brief Get field target_component from set_attitude_target message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const /** * @brief Get field type_mask from set_attitude_target message * - * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude */ static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlin /** * @brief Get field q from set_attitude_target message * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) */ static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q) { @@ -342,7 +342,7 @@ static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_messa /** * @brief Get field body_roll_rate from set_attitude_target message * - * @return Body roll rate in radians per second + * @return [rad/s] Body roll rate */ static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) { @@ -352,7 +352,7 @@ static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mav /** * @brief Get field body_pitch_rate from set_attitude_target message * - * @return Body roll rate in radians per second + * @return [rad/s] Body pitch rate */ static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) { @@ -362,7 +362,7 @@ static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const ma /** * @brief Get field body_yaw_rate from set_attitude_target message * - * @return Body roll rate in radians per second + * @return [rad/s] Body yaw rate */ static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) { @@ -372,7 +372,7 @@ static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavl /** * @brief Get field thrust from set_attitude_target message * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) */ static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_gps_global_origin.h b/lib/main/MAVLink/common/mavlink_msg_set_gps_global_origin.h index a934c19324..7da7fbb510 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_gps_global_origin.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_gps_global_origin.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 -MAVPACKED( + typedef struct __mavlink_set_gps_global_origin_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - uint8_t target_system; /*< System ID*/ -}) mavlink_set_gps_global_origin_t; + int32_t latitude; /*< [degE7] Latitude (WGS84)*/ + int32_t longitude; /*< [degE7] Longitude (WGS84)*/ + int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ + uint8_t target_system; /*< System ID*/ +} mavlink_set_gps_global_origin_t; #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN 13 @@ -26,20 +26,20 @@ typedef struct __mavlink_set_gps_global_origin_t { 48, \ "SET_GPS_GLOBAL_ORIGIN", \ 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ "SET_GPS_GLOBAL_ORIGIN", \ 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_set_gps_global_origin_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param target_system System ID + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param target_system System ID + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t sys * @brief Send a set_gps_global_origin message * @param chan MAVLink channel to send the message * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param target_system System ID + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t /** * @brief Get field target_system from set_gps_global_origin message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const /** * @brief Get field latitude from set_gps_global_origin message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavli /** * @brief Get field longitude from set_gps_global_origin message * - * @return Longitude (WGS84, in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavl /** * @brief Get field altitude from set_gps_global_origin message * - * @return Altitude (AMSL), in meters * 1000 (positive for up) + * @return [mm] Altitude (MSL). Positive for up. */ static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_home_position.h b/lib/main/MAVLink/common/mavlink_msg_set_home_position.h index cd7c8d34c4..7ddcae5a09 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_home_position.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_home_position.h @@ -3,20 +3,20 @@ #define MAVLINK_MSG_ID_SET_HOME_POSITION 243 -MAVPACKED( + typedef struct __mavlink_set_home_position_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - float x; /*< Local X position of this position in the local coordinate frame*/ - float y; /*< Local Y position of this position in the local coordinate frame*/ - float z; /*< Local Z position of this position in the local coordinate frame*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - uint8_t target_system; /*< System ID.*/ -}) mavlink_set_home_position_t; + int32_t latitude; /*< [degE7] Latitude (WGS84)*/ + int32_t longitude; /*< [degE7] Longitude (WGS84)*/ + int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ + float x; /*< [m] Local X position of this position in the local coordinate frame*/ + float y; /*< [m] Local Y position of this position in the local coordinate frame*/ + float z; /*< [m] Local Z position of this position in the local coordinate frame*/ + float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ + float approach_x; /*< [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_y; /*< [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_z; /*< [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + uint8_t target_system; /*< System ID.*/ +} mavlink_set_home_position_t; #define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 #define MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN 53 @@ -33,7 +33,8 @@ typedef struct __mavlink_set_home_position_t { 243, \ "SET_HOME_POSITION", \ 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ @@ -43,14 +44,14 @@ typedef struct __mavlink_set_home_position_t { { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ "SET_HOME_POSITION", \ 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ @@ -60,7 +61,6 @@ typedef struct __mavlink_set_home_position_t { { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ } \ } #endif @@ -71,17 +71,17 @@ typedef struct __mavlink_set_home_position_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param target_system System ID. + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. + * @param x [m] Local X position of this position in the local coordinate frame + * @param y [m] Local Y position of this position in the local coordinate frame + * @param z [m] Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -127,17 +127,17 @@ static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param target_system System ID. + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. + * @param x [m] Local X position of this position in the local coordinate frame + * @param y [m] Local Y position of this position in the local coordinate frame + * @param z [m] Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -209,17 +209,17 @@ static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_ * @brief Send a set_home_position message * @param chan MAVLink channel to send the message * - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param target_system System ID. + * @param latitude [degE7] Latitude (WGS84) + * @param longitude [degE7] Longitude (WGS84) + * @param altitude [mm] Altitude (MSL). Positive for up. + * @param x [m] Local X position of this position in the local coordinate frame + * @param y [m] Local Y position of this position in the local coordinate frame + * @param z [m] Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -320,7 +320,7 @@ static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msg /** * @brief Get field target_system from set_home_position message * - * @return System ID. + * @return System ID. */ static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg) { @@ -330,7 +330,7 @@ static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavl /** * @brief Get field latitude from set_home_position message * - * @return Latitude (WGS84), in degrees * 1E7 + * @return [degE7] Latitude (WGS84) */ static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg) { @@ -340,7 +340,7 @@ static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_m /** * @brief Get field longitude from set_home_position message * - * @return Longitude (WGS84, in degrees * 1E7 + * @return [degE7] Longitude (WGS84) */ static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg) { @@ -350,7 +350,7 @@ static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_ /** * @brief Get field altitude from set_home_position message * - * @return Altitude (AMSL), in meters * 1000 (positive for up) + * @return [mm] Altitude (MSL). Positive for up. */ static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg) { @@ -360,7 +360,7 @@ static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_m /** * @brief Get field x from set_home_position message * - * @return Local X position of this position in the local coordinate frame + * @return [m] Local X position of this position in the local coordinate frame */ static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg) { @@ -370,7 +370,7 @@ static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* /** * @brief Get field y from set_home_position message * - * @return Local Y position of this position in the local coordinate frame + * @return [m] Local Y position of this position in the local coordinate frame */ static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* /** * @brief Get field z from set_home_position message * - * @return Local Z position of this position in the local coordinate frame + * @return [m] Local Z position of this position in the local coordinate frame */ static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg) { @@ -390,7 +390,7 @@ static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* /** * @brief Get field q from set_home_position message * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground */ static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q) { @@ -400,7 +400,7 @@ static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message /** * @brief Get field approach_x from set_home_position message * - * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg) { @@ -410,7 +410,7 @@ static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_m /** * @brief Get field approach_y from set_home_position message * - * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg) { @@ -420,7 +420,7 @@ static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_m /** * @brief Get field approach_z from set_home_position message * - * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. */ static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_mode.h b/lib/main/MAVLink/common/mavlink_msg_set_mode.h index a4c6ef32bf..d2d0874525 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_mode.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_mode.h @@ -3,12 +3,12 @@ #define MAVLINK_MSG_ID_SET_MODE 11 -MAVPACKED( + typedef struct __mavlink_set_mode_t { - uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ - uint8_t target_system; /*< The system setting the mode*/ - uint8_t base_mode; /*< The new base mode*/ -}) mavlink_set_mode_t; + uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ + uint8_t target_system; /*< The system setting the mode*/ + uint8_t base_mode; /*< The new base mode.*/ +} mavlink_set_mode_t; #define MAVLINK_MSG_ID_SET_MODE_LEN 6 #define MAVLINK_MSG_ID_SET_MODE_MIN_LEN 6 @@ -25,18 +25,18 @@ typedef struct __mavlink_set_mode_t { 11, \ "SET_MODE", \ 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_SET_MODE { \ "SET_MODE", \ 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ + { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ } \ } #endif @@ -47,9 +47,9 @@ typedef struct __mavlink_set_mode_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @param target_system The system setting the mode + * @param base_mode The new base mode. + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -81,9 +81,9 @@ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @param target_system The system setting the mode + * @param base_mode The new base mode. + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -141,9 +141,9 @@ static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8 * @brief Send a set_mode message * @param chan MAVLink channel to send the message * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @param target_system The system setting the mode + * @param base_mode The new base mode. + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -216,7 +216,7 @@ static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field target_system from set_mode message * - * @return The system setting the mode + * @return The system setting the mode */ static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) { @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_messa /** * @brief Get field base_mode from set_mode message * - * @return The new base mode + * @return The new base mode. */ static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) { @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t /** * @brief Get field custom_mode from set_mode message * - * @return The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return The new autopilot-specific mode. This field can be ignored by an autopilot. */ static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_position_target_global_int.h b/lib/main/MAVLink/common/mavlink_msg_set_position_target_global_int.h index ec0c9c1a88..3a1523078c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_position_target_global_int.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_position_target_global_int.h @@ -3,25 +3,25 @@ #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86 -MAVPACKED( + typedef struct __mavlink_set_position_target_global_int_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ - int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ - float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -}) mavlink_set_position_target_global_int_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ + int32_t lat_int; /*< [degE7] X Position in WGS84 frame*/ + int32_t lon_int; /*< [degE7] Y Position in WGS84 frame*/ + float alt; /*< [m] Altitude (MSL, Relative to home, or AGL - depending on frame)*/ + float vx; /*< [m/s] X velocity in NED frame*/ + float vy; /*< [m/s] Y velocity in NED frame*/ + float vz; /*< [m/s] Z velocity in NED frame*/ + float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< [rad] yaw setpoint*/ + float yaw_rate; /*< [rad/s] yaw rate setpoint*/ + uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ +} mavlink_set_position_target_global_int_t; #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN 53 @@ -39,6 +39,10 @@ typedef struct __mavlink_set_position_target_global_int_t { "SET_POSITION_TARGET_GLOBAL_INT", \ 16, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ @@ -50,10 +54,6 @@ typedef struct __mavlink_set_position_target_global_int_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ } \ } #else @@ -61,6 +61,10 @@ typedef struct __mavlink_set_position_target_global_int_t { "SET_POSITION_TARGET_GLOBAL_INT", \ 16, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ @@ -72,10 +76,6 @@ typedef struct __mavlink_set_position_target_global_int_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ } \ } #endif @@ -86,22 +86,22 @@ typedef struct __mavlink_set_position_target_global_int_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param lat_int [degE7] X Position in WGS84 frame + * @param lon_int [degE7] Y Position in WGS84 frame + * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -159,22 +159,22 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t s * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param lat_int [degE7] X Position in WGS84 frame + * @param lon_int [degE7] Y Position in WGS84 frame + * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -258,22 +258,22 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(ui * @brief Send a set_position_target_global_int message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param lat_int [degE7] X Position in WGS84 frame + * @param lon_int [degE7] Y Position in WGS84 frame + * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -398,7 +398,7 @@ static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_m /** * @brief Get field time_boot_ms from set_position_target_global_int message * - * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @return [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. */ static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ /** * @brief Get field target_system from set_position_target_global_int message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_syst /** * @brief Get field target_component from set_position_target_global_int message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_comp /** * @brief Get field coordinate_frame from set_position_target_global_int message * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 */ static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) { @@ -438,7 +438,7 @@ static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_ /** * @brief Get field type_mask from set_position_target_global_int message * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @return Bitmap to indicate which dimensions should be ignored by the vehicle. */ static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg) { @@ -448,7 +448,7 @@ static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask( /** * @brief Get field lat_int from set_position_target_global_int message * - * @return X Position in WGS84 frame in 1e7 * meters + * @return [degE7] X Position in WGS84 frame */ static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg) { @@ -458,7 +458,7 @@ static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(con /** * @brief Get field lon_int from set_position_target_global_int message * - * @return Y Position in WGS84 frame in 1e7 * meters + * @return [degE7] Y Position in WGS84 frame */ static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg) { @@ -468,7 +468,7 @@ static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(con /** * @brief Get field alt from set_position_target_global_int message * - * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @return [m] Altitude (MSL, Relative to home, or AGL - depending on frame) */ static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg) { @@ -478,7 +478,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_alt(const mav /** * @brief Get field vx from set_position_target_global_int message * - * @return X velocity in NED frame in meter / s + * @return [m/s] X velocity in NED frame */ static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg) { @@ -488,7 +488,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavl /** * @brief Get field vy from set_position_target_global_int message * - * @return Y velocity in NED frame in meter / s + * @return [m/s] Y velocity in NED frame */ static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg) { @@ -498,7 +498,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavl /** * @brief Get field vz from set_position_target_global_int message * - * @return Z velocity in NED frame in meter / s + * @return [m/s] Z velocity in NED frame */ static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg) { @@ -508,7 +508,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavl /** * @brief Get field afx from set_position_target_global_int message * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg) { @@ -518,7 +518,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_afx(const mav /** * @brief Get field afy from set_position_target_global_int message * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg) { @@ -528,7 +528,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_afy(const mav /** * @brief Get field afz from set_position_target_global_int message * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg) { @@ -538,7 +538,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_afz(const mav /** * @brief Get field yaw from set_position_target_global_int message * - * @return yaw setpoint in rad + * @return [rad] yaw setpoint */ static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg) { @@ -548,7 +548,7 @@ static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mav /** * @brief Get field yaw_rate from set_position_target_global_int message * - * @return yaw rate setpoint in rad/s + * @return [rad/s] yaw rate setpoint */ static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_set_position_target_local_ned.h b/lib/main/MAVLink/common/mavlink_msg_set_position_target_local_ned.h index af4e8d68db..4e16b2ab34 100755 --- a/lib/main/MAVLink/common/mavlink_msg_set_position_target_local_ned.h +++ b/lib/main/MAVLink/common/mavlink_msg_set_position_target_local_ned.h @@ -3,25 +3,25 @@ #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 -MAVPACKED( + typedef struct __mavlink_set_position_target_local_ned_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float x; /*< X Position in NED frame in meters*/ - float y; /*< Y Position in NED frame in meters*/ - float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -}) mavlink_set_position_target_local_ned_t; + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ + float x; /*< [m] X Position in NED frame*/ + float y; /*< [m] Y Position in NED frame*/ + float z; /*< [m] Z Position in NED frame (note, altitude is negative in NED)*/ + float vx; /*< [m/s] X velocity in NED frame*/ + float vy; /*< [m/s] Y velocity in NED frame*/ + float vz; /*< [m/s] Z velocity in NED frame*/ + float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< [rad] yaw setpoint*/ + float yaw_rate; /*< [rad/s] yaw rate setpoint*/ + uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ +} mavlink_set_position_target_local_ned_t; #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN 53 @@ -39,6 +39,10 @@ typedef struct __mavlink_set_position_target_local_ned_t { "SET_POSITION_TARGET_LOCAL_NED", \ 16, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ @@ -50,10 +54,6 @@ typedef struct __mavlink_set_position_target_local_ned_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ } \ } #else @@ -61,6 +61,10 @@ typedef struct __mavlink_set_position_target_local_ned_t { "SET_POSITION_TARGET_LOCAL_NED", \ 16, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ @@ -72,10 +76,6 @@ typedef struct __mavlink_set_position_target_local_ned_t { { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ } \ } #endif @@ -86,22 +86,22 @@ typedef struct __mavlink_set_position_target_local_ned_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param x [m] X Position in NED frame + * @param y [m] Y Position in NED frame + * @param z [m] Z Position in NED frame (note, altitude is negative in NED) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -159,22 +159,22 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t sy * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param x [m] X Position in NED frame + * @param y [m] Y Position in NED frame + * @param z [m] Z Position in NED frame (note, altitude is negative in NED) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -258,22 +258,22 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uin * @brief Send a set_position_target_local_ned message * @param chan MAVLink channel to send the message * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s + * @param time_boot_ms [ms] Timestamp (time since system boot). + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. + * @param x [m] X Position in NED frame + * @param y [m] Y Position in NED frame + * @param z [m] Z Position in NED frame (note, altitude is negative in NED) + * @param vx [m/s] X velocity in NED frame + * @param vy [m/s] Y velocity in NED frame + * @param vz [m/s] Z velocity in NED frame + * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw [rad] yaw setpoint + * @param yaw_rate [rad/s] yaw rate setpoint */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -398,7 +398,7 @@ static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_me /** * @brief Get field time_boot_ms from set_position_target_local_ned message * - * @return Timestamp in milliseconds since system boot + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) { @@ -408,7 +408,7 @@ static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_m /** * @brief Get field target_system from set_position_target_local_ned message * - * @return System ID + * @return System ID */ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg) { @@ -418,7 +418,7 @@ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_syste /** * @brief Get field target_component from set_position_target_local_ned message * - * @return Component ID + * @return Component ID */ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg) { @@ -428,7 +428,7 @@ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_compo /** * @brief Get field coordinate_frame from set_position_target_local_ned message * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 */ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) { @@ -438,7 +438,7 @@ static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_f /** * @brief Get field type_mask from set_position_target_local_ned message * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @return Bitmap to indicate which dimensions should be ignored by the vehicle. */ static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) { @@ -448,7 +448,7 @@ static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(c /** * @brief Get field x from set_position_target_local_ned message * - * @return X Position in NED frame in meters + * @return [m] X Position in NED frame */ static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg) { @@ -458,7 +458,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlin /** * @brief Get field y from set_position_target_local_ned message * - * @return Y Position in NED frame in meters + * @return [m] Y Position in NED frame */ static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg) { @@ -468,7 +468,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlin /** * @brief Get field z from set_position_target_local_ned message * - * @return Z Position in NED frame in meters (note, altitude is negative in NED) + * @return [m] Z Position in NED frame (note, altitude is negative in NED) */ static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg) { @@ -478,7 +478,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlin /** * @brief Get field vx from set_position_target_local_ned message * - * @return X velocity in NED frame in meter / s + * @return [m/s] X velocity in NED frame */ static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg) { @@ -488,7 +488,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavli /** * @brief Get field vy from set_position_target_local_ned message * - * @return Y velocity in NED frame in meter / s + * @return [m/s] Y velocity in NED frame */ static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg) { @@ -498,7 +498,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavli /** * @brief Get field vz from set_position_target_local_ned message * - * @return Z velocity in NED frame in meter / s + * @return [m/s] Z velocity in NED frame */ static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg) { @@ -508,7 +508,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavli /** * @brief Get field afx from set_position_target_local_ned message * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg) { @@ -518,7 +518,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavl /** * @brief Get field afy from set_position_target_local_ned message * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg) { @@ -528,7 +528,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavl /** * @brief Get field afz from set_position_target_local_ned message * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg) { @@ -538,7 +538,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavl /** * @brief Get field yaw from set_position_target_local_ned message * - * @return yaw setpoint in rad + * @return [rad] yaw setpoint */ static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg) { @@ -548,7 +548,7 @@ static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavl /** * @brief Get field yaw_rate from set_position_target_local_ned message * - * @return yaw rate setpoint in rad/s + * @return [rad/s] yaw rate setpoint */ static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_sim_state.h b/lib/main/MAVLink/common/mavlink_msg_sim_state.h index e49a07f1f4..b128b8d54b 100755 --- a/lib/main/MAVLink/common/mavlink_msg_sim_state.h +++ b/lib/main/MAVLink/common/mavlink_msg_sim_state.h @@ -3,30 +3,30 @@ #define MAVLINK_MSG_ID_SIM_STATE 108 -MAVPACKED( + typedef struct __mavlink_sim_state_t { - float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ - float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ - float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ - float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ - float xacc; /*< X acceleration m/s/s*/ - float yacc; /*< Y acceleration m/s/s*/ - float zacc; /*< Z acceleration m/s/s*/ - float xgyro; /*< Angular speed around X axis rad/s*/ - float ygyro; /*< Angular speed around Y axis rad/s*/ - float zgyro; /*< Angular speed around Z axis rad/s*/ - float lat; /*< Latitude in degrees*/ - float lon; /*< Longitude in degrees*/ - float alt; /*< Altitude in meters*/ - float std_dev_horz; /*< Horizontal position standard deviation*/ - float std_dev_vert; /*< Vertical position standard deviation*/ - float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/ - float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/ - float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/ -}) mavlink_sim_state_t; + float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ + float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ + float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ + float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ + float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ + float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ + float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ + float xacc; /*< [m/s/s] X acceleration*/ + float yacc; /*< [m/s/s] Y acceleration*/ + float zacc; /*< [m/s/s] Z acceleration*/ + float xgyro; /*< [rad/s] Angular speed around X axis*/ + float ygyro; /*< [rad/s] Angular speed around Y axis*/ + float zgyro; /*< [rad/s] Angular speed around Z axis*/ + float lat; /*< [deg] Latitude*/ + float lon; /*< [deg] Longitude*/ + float alt; /*< [m] Altitude*/ + float std_dev_horz; /*< Horizontal position standard deviation*/ + float std_dev_vert; /*< Vertical position standard deviation*/ + float vn; /*< [m/s] True velocity in north direction in earth-fixed NED frame*/ + float ve; /*< [m/s] True velocity in east direction in earth-fixed NED frame*/ + float vd; /*< [m/s] True velocity in down direction in earth-fixed NED frame*/ +} mavlink_sim_state_t; #define MAVLINK_MSG_ID_SIM_STATE_LEN 84 #define MAVLINK_MSG_ID_SIM_STATE_MIN_LEN 84 @@ -101,27 +101,27 @@ typedef struct __mavlink_sim_state_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis + * @param ygyro [rad/s] Angular speed around Y axis + * @param zgyro [rad/s] Angular speed around Z axis + * @param lat [deg] Latitude + * @param lon [deg] Longitude + * @param alt [m] Altitude + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn [m/s] True velocity in north direction in earth-fixed NED frame + * @param ve [m/s] True velocity in east direction in earth-fixed NED frame + * @param vd [m/s] True velocity in down direction in earth-fixed NED frame * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -189,27 +189,27 @@ static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis + * @param ygyro [rad/s] Angular speed around Y axis + * @param zgyro [rad/s] Angular speed around Z axis + * @param lat [deg] Latitude + * @param lon [deg] Longitude + * @param alt [m] Altitude + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn [m/s] True velocity in north direction in earth-fixed NED frame + * @param ve [m/s] True velocity in east direction in earth-fixed NED frame + * @param vd [m/s] True velocity in down direction in earth-fixed NED frame * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -303,27 +303,27 @@ static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint * @brief Send a sim_state message * @param chan MAVLink channel to send the message * - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc [m/s/s] X acceleration + * @param yacc [m/s/s] Y acceleration + * @param zacc [m/s/s] Z acceleration + * @param xgyro [rad/s] Angular speed around X axis + * @param ygyro [rad/s] Angular speed around Y axis + * @param zgyro [rad/s] Angular speed around Z axis + * @param lat [deg] Latitude + * @param lon [deg] Longitude + * @param alt [m] Altitude + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn [m/s] True velocity in north direction in earth-fixed NED frame + * @param ve [m/s] True velocity in east direction in earth-fixed NED frame + * @param vd [m/s] True velocity in down direction in earth-fixed NED frame */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -468,7 +468,7 @@ static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field q1 from sim_state message * - * @return True attitude quaternion component 1, w (1 in null-rotation) + * @return True attitude quaternion component 1, w (1 in null-rotation) */ static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) { @@ -478,7 +478,7 @@ static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) /** * @brief Get field q2 from sim_state message * - * @return True attitude quaternion component 2, x (0 in null-rotation) + * @return True attitude quaternion component 2, x (0 in null-rotation) */ static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) { @@ -488,7 +488,7 @@ static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) /** * @brief Get field q3 from sim_state message * - * @return True attitude quaternion component 3, y (0 in null-rotation) + * @return True attitude quaternion component 3, y (0 in null-rotation) */ static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) { @@ -498,7 +498,7 @@ static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) /** * @brief Get field q4 from sim_state message * - * @return True attitude quaternion component 4, z (0 in null-rotation) + * @return True attitude quaternion component 4, z (0 in null-rotation) */ static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) { @@ -508,7 +508,7 @@ static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) /** * @brief Get field roll from sim_state message * - * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs */ static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) { @@ -518,7 +518,7 @@ static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) /** * @brief Get field pitch from sim_state message * - * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs */ static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) { @@ -528,7 +528,7 @@ static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg /** * @brief Get field yaw from sim_state message * - * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs */ static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) { @@ -538,7 +538,7 @@ static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) /** * @brief Get field xacc from sim_state message * - * @return X acceleration m/s/s + * @return [m/s/s] X acceleration */ static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) { @@ -548,7 +548,7 @@ static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) /** * @brief Get field yacc from sim_state message * - * @return Y acceleration m/s/s + * @return [m/s/s] Y acceleration */ static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) { @@ -558,7 +558,7 @@ static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) /** * @brief Get field zacc from sim_state message * - * @return Z acceleration m/s/s + * @return [m/s/s] Z acceleration */ static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) { @@ -568,7 +568,7 @@ static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) /** * @brief Get field xgyro from sim_state message * - * @return Angular speed around X axis rad/s + * @return [rad/s] Angular speed around X axis */ static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg) { @@ -578,7 +578,7 @@ static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg /** * @brief Get field ygyro from sim_state message * - * @return Angular speed around Y axis rad/s + * @return [rad/s] Angular speed around Y axis */ static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg) { @@ -588,7 +588,7 @@ static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg /** * @brief Get field zgyro from sim_state message * - * @return Angular speed around Z axis rad/s + * @return [rad/s] Angular speed around Z axis */ static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg) { @@ -598,7 +598,7 @@ static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg /** * @brief Get field lat from sim_state message * - * @return Latitude in degrees + * @return [deg] Latitude */ static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) { @@ -608,7 +608,7 @@ static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) /** * @brief Get field lon from sim_state message * - * @return Longitude in degrees + * @return [deg] Longitude */ static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) { @@ -618,7 +618,7 @@ static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) /** * @brief Get field alt from sim_state message * - * @return Altitude in meters + * @return [m] Altitude */ static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) { @@ -628,7 +628,7 @@ static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) /** * @brief Get field std_dev_horz from sim_state message * - * @return Horizontal position standard deviation + * @return Horizontal position standard deviation */ static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) { @@ -638,7 +638,7 @@ static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message /** * @brief Get field std_dev_vert from sim_state message * - * @return Vertical position standard deviation + * @return Vertical position standard deviation */ static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) { @@ -648,7 +648,7 @@ static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message /** * @brief Get field vn from sim_state message * - * @return True velocity in m/s in NORTH direction in earth-fixed NED frame + * @return [m/s] True velocity in north direction in earth-fixed NED frame */ static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) { @@ -658,7 +658,7 @@ static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) /** * @brief Get field ve from sim_state message * - * @return True velocity in m/s in EAST direction in earth-fixed NED frame + * @return [m/s] True velocity in east direction in earth-fixed NED frame */ static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) { @@ -668,7 +668,7 @@ static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) /** * @brief Get field vd from sim_state message * - * @return True velocity in m/s in DOWN direction in earth-fixed NED frame + * @return [m/s] True velocity in down direction in earth-fixed NED frame */ static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_statustext.h b/lib/main/MAVLink/common/mavlink_msg_statustext.h index e1ed320a3d..2193fac839 100755 --- a/lib/main/MAVLink/common/mavlink_msg_statustext.h +++ b/lib/main/MAVLink/common/mavlink_msg_statustext.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_STATUSTEXT 253 -MAVPACKED( + typedef struct __mavlink_statustext_t { - uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.*/ - char text[50]; /*< Status text message, without null termination character*/ -}) mavlink_statustext_t; + uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424.*/ + char text[50]; /*< Status text message, without null termination character*/ +} mavlink_statustext_t; #define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 #define MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN 51 @@ -44,8 +44,8 @@ typedef struct __mavlink_statustext_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character + * @param severity Severity of status. Relies on the definitions within RFC-5424. + * @param text Status text message, without null termination character * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -73,8 +73,8 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character + * @param severity Severity of status. Relies on the definitions within RFC-5424. + * @param text Status text message, without null termination character * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -128,8 +128,8 @@ static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uin * @brief Send a statustext message * @param chan MAVLink channel to send the message * - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character + * @param severity Severity of status. Relies on the definitions within RFC-5424. + * @param text Status text message, without null termination character */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -194,7 +194,7 @@ static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field severity from statustext message * - * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @return Severity of status. Relies on the definitions within RFC-5424. */ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) { @@ -204,7 +204,7 @@ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_ /** * @brief Get field text from statustext message * - * @return Status text message, without null termination character + * @return Status text message, without null termination character */ static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) { diff --git a/lib/main/MAVLink/common/mavlink_msg_sys_status.h b/lib/main/MAVLink/common/mavlink_msg_sys_status.h index 28a85b53f5..301302a14c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_sys_status.h +++ b/lib/main/MAVLink/common/mavlink_msg_sys_status.h @@ -3,22 +3,22 @@ #define MAVLINK_MSG_ID_SYS_STATUS 1 -MAVPACKED( + typedef struct __mavlink_sys_status_t { - uint32_t onboard_control_sensors_present; /*< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint32_t onboard_control_sensors_enabled; /*< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint32_t onboard_control_sensors_health; /*< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint16_t load; /*< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000*/ - uint16_t voltage_battery; /*< Battery voltage, in millivolts (1 = 1 millivolt)*/ - int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ - uint16_t drop_rate_comm; /*< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_count1; /*< Autopilot-specific errors*/ - uint16_t errors_count2; /*< Autopilot-specific errors*/ - uint16_t errors_count3; /*< Autopilot-specific errors*/ - uint16_t errors_count4; /*< Autopilot-specific errors*/ - int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery*/ -}) mavlink_sys_status_t; + uint32_t onboard_control_sensors_present; /*< Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.*/ + uint32_t onboard_control_sensors_enabled; /*< Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.*/ + uint32_t onboard_control_sensors_health; /*< Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.*/ + uint16_t load; /*< [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000*/ + uint16_t voltage_battery; /*< [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot*/ + int16_t current_battery; /*< [cA] Battery current, -1: Current not sent by autopilot*/ + uint16_t drop_rate_comm; /*< [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ + uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ + uint16_t errors_count1; /*< Autopilot-specific errors*/ + uint16_t errors_count2; /*< Autopilot-specific errors*/ + uint16_t errors_count3; /*< Autopilot-specific errors*/ + uint16_t errors_count4; /*< Autopilot-specific errors*/ + int8_t battery_remaining; /*< [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot*/ +} mavlink_sys_status_t; #define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 #define MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN 31 @@ -41,13 +41,13 @@ typedef struct __mavlink_sys_status_t { { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ } \ } #else @@ -60,13 +60,13 @@ typedef struct __mavlink_sys_status_t { { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ } \ } #endif @@ -77,19 +77,19 @@ typedef struct __mavlink_sys_status_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors + * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. + * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. + * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. + * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 + * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot + * @param current_battery [cA] Battery current, -1: Current not sent by autopilot + * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot + * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -141,19 +141,19 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors + * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. + * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. + * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. + * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 + * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot + * @param current_battery [cA] Battery current, -1: Current not sent by autopilot + * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot + * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -231,19 +231,19 @@ static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uin * @brief Send a sys_status message * @param chan MAVLink channel to send the message * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors + * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. + * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. + * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. + * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 + * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot + * @param current_battery [cA] Battery current, -1: Current not sent by autopilot + * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot + * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -356,7 +356,7 @@ static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field onboard_control_sensors_present from sys_status message * - * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @return Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. */ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) { @@ -366,7 +366,7 @@ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_presen /** * @brief Get field onboard_control_sensors_enabled from sys_status message * - * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @return Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. */ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) { @@ -376,7 +376,7 @@ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enable /** * @brief Get field onboard_control_sensors_health from sys_status message * - * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @return Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. */ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) { @@ -386,7 +386,7 @@ static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health /** * @brief Get field load from sys_status message * - * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @return [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 */ static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) { @@ -396,7 +396,7 @@ static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* /** * @brief Get field voltage_battery from sys_status message * - * @return Battery voltage, in millivolts (1 = 1 millivolt) + * @return [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot */ static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) { @@ -406,7 +406,7 @@ static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_ /** * @brief Get field current_battery from sys_status message * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @return [cA] Battery current, -1: Current not sent by autopilot */ static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) { @@ -416,7 +416,7 @@ static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_m /** * @brief Get field battery_remaining from sys_status message * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @return [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot */ static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) { @@ -426,7 +426,7 @@ static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_ /** * @brief Get field drop_rate_comm from sys_status message * - * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @return [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) */ static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) { @@ -436,7 +436,7 @@ static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_m /** * @brief Get field errors_comm from sys_status message * - * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) */ static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) { @@ -446,7 +446,7 @@ static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_mess /** * @brief Get field errors_count1 from sys_status message * - * @return Autopilot-specific errors + * @return Autopilot-specific errors */ static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) { @@ -456,7 +456,7 @@ static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_me /** * @brief Get field errors_count2 from sys_status message * - * @return Autopilot-specific errors + * @return Autopilot-specific errors */ static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) { @@ -466,7 +466,7 @@ static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_me /** * @brief Get field errors_count3 from sys_status message * - * @return Autopilot-specific errors + * @return Autopilot-specific errors */ static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) { @@ -476,7 +476,7 @@ static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_me /** * @brief Get field errors_count4 from sys_status message * - * @return Autopilot-specific errors + * @return Autopilot-specific errors */ static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_system_time.h b/lib/main/MAVLink/common/mavlink_msg_system_time.h index 0e9b2ce5a8..a3848c7419 100755 --- a/lib/main/MAVLink/common/mavlink_msg_system_time.h +++ b/lib/main/MAVLink/common/mavlink_msg_system_time.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_SYSTEM_TIME 2 -MAVPACKED( + typedef struct __mavlink_system_time_t { - uint64_t time_unix_usec; /*< Timestamp of the master clock in microseconds since UNIX epoch.*/ - uint32_t time_boot_ms; /*< Timestamp of the component clock since boot time in milliseconds.*/ -}) mavlink_system_time_t; + uint64_t time_unix_usec; /*< [us] Timestamp (UNIX epoch time).*/ + uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ +} mavlink_system_time_t; #define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 #define MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN 12 @@ -44,8 +44,8 @@ typedef struct __mavlink_system_time_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @param time_unix_usec [us] Timestamp (UNIX epoch time). + * @param time_boot_ms [ms] Timestamp (time since system boot). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @param time_unix_usec [us] Timestamp (UNIX epoch time). + * @param time_boot_ms [ms] Timestamp (time since system boot). * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, ui * @brief Send a system_time message * @param chan MAVLink channel to send the message * - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @param time_unix_usec [us] Timestamp (UNIX epoch time). + * @param time_boot_ms [ms] Timestamp (time since system boot). */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field time_unix_usec from system_time message * - * @return Timestamp of the master clock in microseconds since UNIX epoch. + * @return [us] Timestamp (UNIX epoch time). */ static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_ /** * @brief Get field time_boot_ms from system_time message * - * @return Timestamp of the component clock since boot time in milliseconds. + * @return [ms] Timestamp (time since system boot). */ static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_terrain_check.h b/lib/main/MAVLink/common/mavlink_msg_terrain_check.h index 820ff336c5..74afd52eea 100755 --- a/lib/main/MAVLink/common/mavlink_msg_terrain_check.h +++ b/lib/main/MAVLink/common/mavlink_msg_terrain_check.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_TERRAIN_CHECK 135 -MAVPACKED( + typedef struct __mavlink_terrain_check_t { - int32_t lat; /*< Latitude (degrees *10^7)*/ - int32_t lon; /*< Longitude (degrees *10^7)*/ -}) mavlink_terrain_check_t; + int32_t lat; /*< [degE7] Latitude*/ + int32_t lon; /*< [degE7] Longitude*/ +} mavlink_terrain_check_t; #define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 #define MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN 8 @@ -44,8 +44,8 @@ typedef struct __mavlink_terrain_check_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, * @brief Send a terrain_check message * @param chan MAVLink channel to send the message * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field lat from terrain_check message * - * @return Latitude (degrees *10^7) + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* /** * @brief Get field lon from terrain_check message * - * @return Longitude (degrees *10^7) + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_terrain_data.h b/lib/main/MAVLink/common/mavlink_msg_terrain_data.h index ac9b9be650..3099502cab 100755 --- a/lib/main/MAVLink/common/mavlink_msg_terrain_data.h +++ b/lib/main/MAVLink/common/mavlink_msg_terrain_data.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_TERRAIN_DATA 134 -MAVPACKED( + typedef struct __mavlink_terrain_data_t { - int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ - int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ - uint16_t grid_spacing; /*< Grid spacing in meters*/ - int16_t data[16]; /*< Terrain data in meters AMSL*/ - uint8_t gridbit; /*< bit within the terrain request mask*/ -}) mavlink_terrain_data_t; + int32_t lat; /*< [degE7] Latitude of SW corner of first grid*/ + int32_t lon; /*< [degE7] Longitude of SW corner of first grid*/ + uint16_t grid_spacing; /*< [m] Grid spacing*/ + int16_t data[16]; /*< [m] Terrain data MSL*/ + uint8_t gridbit; /*< bit within the terrain request mask*/ +} mavlink_terrain_data_t; #define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 #define MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN 43 @@ -30,8 +30,8 @@ typedef struct __mavlink_terrain_data_t { { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ + { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ } \ } #else @@ -41,8 +41,8 @@ typedef struct __mavlink_terrain_data_t { { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ + { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ } \ } #endif @@ -53,11 +53,11 @@ typedef struct __mavlink_terrain_data_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL + * @param lat [degE7] Latitude of SW corner of first grid + * @param lon [degE7] Longitude of SW corner of first grid + * @param grid_spacing [m] Grid spacing + * @param gridbit bit within the terrain request mask + * @param data [m] Terrain data MSL * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL + * @param lat [degE7] Latitude of SW corner of first grid + * @param lon [degE7] Longitude of SW corner of first grid + * @param grid_spacing [m] Grid spacing + * @param gridbit bit within the terrain request mask + * @param data [m] Terrain data MSL * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, u * @brief Send a terrain_data message * @param chan MAVLink channel to send the message * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL + * @param lat [degE7] Latitude of SW corner of first grid + * @param lon [degE7] Longitude of SW corner of first grid + * @param grid_spacing [m] Grid spacing + * @param gridbit bit within the terrain request mask + * @param data [m] Terrain data MSL */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field lat from terrain_data message * - * @return Latitude of SW corner of first grid (degrees *10^7) + * @return [degE7] Latitude of SW corner of first grid */ static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg) { @@ -246,7 +246,7 @@ static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* /** * @brief Get field lon from terrain_data message * - * @return Longitude of SW corner of first grid (in degrees *10^7) + * @return [degE7] Longitude of SW corner of first grid */ static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg) { @@ -256,7 +256,7 @@ static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* /** * @brief Get field grid_spacing from terrain_data message * - * @return Grid spacing in meters + * @return [m] Grid spacing */ static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg) { @@ -266,7 +266,7 @@ static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_m /** * @brief Get field gridbit from terrain_data message * - * @return bit within the terrain request mask + * @return bit within the terrain request mask */ static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message /** * @brief Get field data from terrain_data message * - * @return Terrain data in meters AMSL + * @return [m] Terrain data MSL */ static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data) { diff --git a/lib/main/MAVLink/common/mavlink_msg_terrain_report.h b/lib/main/MAVLink/common/mavlink_msg_terrain_report.h index 1374db5bc0..8757a75a27 100755 --- a/lib/main/MAVLink/common/mavlink_msg_terrain_report.h +++ b/lib/main/MAVLink/common/mavlink_msg_terrain_report.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_TERRAIN_REPORT 136 -MAVPACKED( + typedef struct __mavlink_terrain_report_t { - int32_t lat; /*< Latitude (degrees *10^7)*/ - int32_t lon; /*< Longitude (degrees *10^7)*/ - float terrain_height; /*< Terrain height in meters AMSL*/ - float current_height; /*< Current vehicle height above lat/lon terrain height (meters)*/ - uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ - uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ - uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ -}) mavlink_terrain_report_t; + int32_t lat; /*< [degE7] Latitude*/ + int32_t lon; /*< [degE7] Longitude*/ + float terrain_height; /*< [m] Terrain height MSL*/ + float current_height; /*< [m] Current vehicle height above lat/lon terrain height*/ + uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ + uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ + uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ +} mavlink_terrain_report_t; #define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 #define MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN 22 @@ -31,9 +31,9 @@ typedef struct __mavlink_terrain_report_t { 7, \ { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ + { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ } \ @@ -44,9 +44,9 @@ typedef struct __mavlink_terrain_report_t { 7, \ { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ + { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ } \ @@ -59,13 +59,13 @@ typedef struct __mavlink_terrain_report_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height [m] Terrain height MSL + * @param current_height [m] Current vehicle height above lat/lon terrain height + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height [m] Terrain height MSL + * @param current_height [m] Current vehicle height above lat/lon terrain height + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, * @brief Send a terrain_report message * @param chan MAVLink channel to send the message * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory + * @param lat [degE7] Latitude + * @param lon [degE7] Longitude + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height [m] Terrain height MSL + * @param current_height [m] Current vehicle height above lat/lon terrain height + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf /** * @brief Get field lat from terrain_report message * - * @return Latitude (degrees *10^7) + * @return [degE7] Latitude */ static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t /** * @brief Get field lon from terrain_report message * - * @return Longitude (degrees *10^7) + * @return [degE7] Longitude */ static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t /** * @brief Get field spacing from terrain_report message * - * @return grid spacing (zero if terrain at this location unavailable) + * @return grid spacing (zero if terrain at this location unavailable) */ static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_mess /** * @brief Get field terrain_height from terrain_report message * - * @return Terrain height in meters AMSL + * @return [m] Terrain height MSL */ static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_ /** * @brief Get field current_height from terrain_report message * - * @return Current vehicle height above lat/lon terrain height (meters) + * @return [m] Current vehicle height above lat/lon terrain height */ static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_ /** * @brief Get field pending from terrain_report message * - * @return Number of 4x4 terrain blocks waiting to be received or read from disk + * @return Number of 4x4 terrain blocks waiting to be received or read from disk */ static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_mess /** * @brief Get field loaded from terrain_report message * - * @return Number of 4x4 terrain blocks in memory + * @return Number of 4x4 terrain blocks in memory */ static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_terrain_request.h b/lib/main/MAVLink/common/mavlink_msg_terrain_request.h index 8924ed4f19..9889edd7d0 100755 --- a/lib/main/MAVLink/common/mavlink_msg_terrain_request.h +++ b/lib/main/MAVLink/common/mavlink_msg_terrain_request.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 -MAVPACKED( + typedef struct __mavlink_terrain_request_t { - uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ - int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ - int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ - uint16_t grid_spacing; /*< Grid spacing in meters*/ -}) mavlink_terrain_request_t; + uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ + int32_t lat; /*< [degE7] Latitude of SW corner of first grid*/ + int32_t lon; /*< [degE7] Longitude of SW corner of first grid*/ + uint16_t grid_spacing; /*< [m] Grid spacing*/ +} mavlink_terrain_request_t; #define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 #define MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN 18 @@ -26,20 +26,20 @@ typedef struct __mavlink_terrain_request_t { 133, \ "TERRAIN_REQUEST", \ 4, \ - { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ + { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ "TERRAIN_REQUEST", \ 4, \ - { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ + { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ } \ } #endif @@ -50,10 +50,10 @@ typedef struct __mavlink_terrain_request_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @param lat [degE7] Latitude of SW corner of first grid + * @param lon [degE7] Longitude of SW corner of first grid + * @param grid_spacing [m] Grid spacing + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @param lat [degE7] Latitude of SW corner of first grid + * @param lon [degE7] Longitude of SW corner of first grid + * @param grid_spacing [m] Grid spacing + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id * @brief Send a terrain_request message * @param chan MAVLink channel to send the message * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @param lat [degE7] Latitude of SW corner of first grid + * @param lon [degE7] Longitude of SW corner of first grid + * @param grid_spacing [m] Grid spacing + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbu /** * @brief Get field lat from terrain_request message * - * @return Latitude of SW corner of first grid (degrees *10^7) + * @return [degE7] Latitude of SW corner of first grid */ static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_ /** * @brief Get field lon from terrain_request message * - * @return Longitude of SW corner of first grid (in degrees *10^7) + * @return [degE7] Longitude of SW corner of first grid */ static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_ /** * @brief Get field grid_spacing from terrain_request message * - * @return Grid spacing in meters + * @return [m] Grid spacing */ static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlin /** * @brief Get field mask from terrain_request message * - * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) */ static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_timesync.h b/lib/main/MAVLink/common/mavlink_msg_timesync.h index 395211fd8b..a9de47dd45 100755 --- a/lib/main/MAVLink/common/mavlink_msg_timesync.h +++ b/lib/main/MAVLink/common/mavlink_msg_timesync.h @@ -3,11 +3,11 @@ #define MAVLINK_MSG_ID_TIMESYNC 111 -MAVPACKED( + typedef struct __mavlink_timesync_t { - int64_t tc1; /*< Time sync timestamp 1*/ - int64_t ts1; /*< Time sync timestamp 2*/ -}) mavlink_timesync_t; + int64_t tc1; /*< Time sync timestamp 1*/ + int64_t ts1; /*< Time sync timestamp 2*/ +} mavlink_timesync_t; #define MAVLINK_MSG_ID_TIMESYNC_LEN 16 #define MAVLINK_MSG_ID_TIMESYNC_MIN_LEN 16 @@ -44,8 +44,8 @@ typedef struct __mavlink_timesync_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -75,8 +75,8 @@ static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -132,8 +132,8 @@ static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8 * @brief Send a timesync message * @param chan MAVLink channel to send the message * - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -202,7 +202,7 @@ static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field tc1 from timesync message * - * @return Time sync timestamp 1 + * @return Time sync timestamp 1 */ static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) { @@ -212,7 +212,7 @@ static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) /** * @brief Get field ts1 from timesync message * - * @return Time sync timestamp 2 + * @return Time sync timestamp 2 */ static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_v2_extension.h b/lib/main/MAVLink/common/mavlink_msg_v2_extension.h index 31777f2d9c..689e891146 100755 --- a/lib/main/MAVLink/common/mavlink_msg_v2_extension.h +++ b/lib/main/MAVLink/common/mavlink_msg_v2_extension.h @@ -3,14 +3,14 @@ #define MAVLINK_MSG_ID_V2_EXTENSION 248 -MAVPACKED( + typedef struct __mavlink_v2_extension_t { - uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ -}) mavlink_v2_extension_t; + uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ + uint8_t target_network; /*< Network ID (0 for broadcast)*/ + uint8_t target_system; /*< System ID (0 for broadcast)*/ + uint8_t target_component; /*< Component ID (0 for broadcast)*/ + uint8_t payload[249]; /*< Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification.*/ +} mavlink_v2_extension_t; #define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254 #define MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN 254 @@ -27,10 +27,10 @@ typedef struct __mavlink_v2_extension_t { 248, \ "V2_EXTENSION", \ 5, \ - { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ + { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ + { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ } \ } @@ -38,10 +38,10 @@ typedef struct __mavlink_v2_extension_t { #define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ "V2_EXTENSION", \ 5, \ - { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ + { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ + { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ } \ } @@ -53,11 +53,11 @@ typedef struct __mavlink_v2_extension_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -91,11 +91,11 @@ static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -155,11 +155,11 @@ static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, u * @brief Send a v2_extension message * @param chan MAVLink channel to send the message * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -236,7 +236,7 @@ static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field target_network from v2_extension message * - * @return Network ID (0 for broadcast) + * @return Network ID (0 for broadcast) */ static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg) { @@ -246,7 +246,7 @@ static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_ /** * @brief Get field target_system from v2_extension message * - * @return System ID (0 for broadcast) + * @return System ID (0 for broadcast) */ static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg) { @@ -256,7 +256,7 @@ static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_m /** * @brief Get field target_component from v2_extension message * - * @return Component ID (0 for broadcast) + * @return Component ID (0 for broadcast) */ static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg) { @@ -266,7 +266,7 @@ static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlin /** * @brief Get field message_type from v2_extension message * - * @return A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @return A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. */ static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg) { @@ -276,7 +276,7 @@ static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_m /** * @brief Get field payload from v2_extension message * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. */ static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload) { diff --git a/lib/main/MAVLink/common/mavlink_msg_vfr_hud.h b/lib/main/MAVLink/common/mavlink_msg_vfr_hud.h index 1700dd0aa2..f1706ea65c 100755 --- a/lib/main/MAVLink/common/mavlink_msg_vfr_hud.h +++ b/lib/main/MAVLink/common/mavlink_msg_vfr_hud.h @@ -3,15 +3,15 @@ #define MAVLINK_MSG_ID_VFR_HUD 74 -MAVPACKED( + typedef struct __mavlink_vfr_hud_t { - float airspeed; /*< Current airspeed in m/s*/ - float groundspeed; /*< Current ground speed in m/s*/ - float alt; /*< Current altitude (MSL), in meters*/ - float climb; /*< Current climb rate in meters/second*/ - int16_t heading; /*< Current heading in degrees, in compass units (0..360, 0=north)*/ - uint16_t throttle; /*< Current throttle setting in integer percent, 0 to 100*/ -}) mavlink_vfr_hud_t; + float airspeed; /*< [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.*/ + float groundspeed; /*< [m/s] Current ground speed.*/ + float alt; /*< [m] Current altitude (MSL).*/ + float climb; /*< [m/s] Current climb rate.*/ + int16_t heading; /*< [deg] Current heading in compass units (0-360, 0=north).*/ + uint16_t throttle; /*< [%] Current throttle setting (0 to 100).*/ +} mavlink_vfr_hud_t; #define MAVLINK_MSG_ID_VFR_HUD_LEN 20 #define MAVLINK_MSG_ID_VFR_HUD_MIN_LEN 20 @@ -30,10 +30,10 @@ typedef struct __mavlink_vfr_hud_t { 6, \ { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ } \ } #else @@ -42,10 +42,10 @@ typedef struct __mavlink_vfr_hud_t { 6, \ { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ } \ } #endif @@ -56,12 +56,12 @@ typedef struct __mavlink_vfr_hud_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second + * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. + * @param groundspeed [m/s] Current ground speed. + * @param heading [deg] Current heading in compass units (0-360, 0=north). + * @param throttle [%] Current throttle setting (0 to 100). + * @param alt [m] Current altitude (MSL). + * @param climb [m/s] Current climb rate. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -99,12 +99,12 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second + * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. + * @param groundspeed [m/s] Current ground speed. + * @param heading [deg] Current heading in compass units (0-360, 0=north). + * @param throttle [%] Current throttle setting (0 to 100). + * @param alt [m] Current altitude (MSL). + * @param climb [m/s] Current climb rate. * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -168,12 +168,12 @@ static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_ * @brief Send a vfr_hud message * @param chan MAVLink channel to send the message * - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second + * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. + * @param groundspeed [m/s] Current ground speed. + * @param heading [deg] Current heading in compass units (0-360, 0=north). + * @param throttle [%] Current throttle setting (0 to 100). + * @param alt [m] Current altitude (MSL). + * @param climb [m/s] Current climb rate. */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -258,7 +258,7 @@ static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, mavli /** * @brief Get field airspeed from vfr_hud message * - * @return Current airspeed in m/s + * @return [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. */ static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) { @@ -268,7 +268,7 @@ static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* ms /** * @brief Get field groundspeed from vfr_hud message * - * @return Current ground speed in m/s + * @return [m/s] Current ground speed. */ static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) { @@ -278,7 +278,7 @@ static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* /** * @brief Get field heading from vfr_hud message * - * @return Current heading in degrees, in compass units (0..360, 0=north) + * @return [deg] Current heading in compass units (0-360, 0=north). */ static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) { @@ -288,7 +288,7 @@ static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* m /** * @brief Get field throttle from vfr_hud message * - * @return Current throttle setting in integer percent, 0 to 100 + * @return [%] Current throttle setting (0 to 100). */ static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) { @@ -298,7 +298,7 @@ static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* /** * @brief Get field alt from vfr_hud message * - * @return Current altitude (MSL), in meters + * @return [m] Current altitude (MSL). */ static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) { @@ -308,7 +308,7 @@ static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) /** * @brief Get field climb from vfr_hud message * - * @return Current climb rate in meters/second + * @return [m/s] Current climb rate. */ static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_vibration.h b/lib/main/MAVLink/common/mavlink_msg_vibration.h index a8760f79e5..acc99c4f63 100755 --- a/lib/main/MAVLink/common/mavlink_msg_vibration.h +++ b/lib/main/MAVLink/common/mavlink_msg_vibration.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_VIBRATION 241 -MAVPACKED( + typedef struct __mavlink_vibration_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float vibration_x; /*< Vibration levels on X-axis*/ - float vibration_y; /*< Vibration levels on Y-axis*/ - float vibration_z; /*< Vibration levels on Z-axis*/ - uint32_t clipping_0; /*< first accelerometer clipping count*/ - uint32_t clipping_1; /*< second accelerometer clipping count*/ - uint32_t clipping_2; /*< third accelerometer clipping count*/ -}) mavlink_vibration_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float vibration_x; /*< Vibration levels on X-axis*/ + float vibration_y; /*< Vibration levels on Y-axis*/ + float vibration_z; /*< Vibration levels on Z-axis*/ + uint32_t clipping_0; /*< first accelerometer clipping count*/ + uint32_t clipping_1; /*< second accelerometer clipping count*/ + uint32_t clipping_2; /*< third accelerometer clipping count*/ +} mavlink_vibration_t; #define MAVLINK_MSG_ID_VIBRATION_LEN 32 #define MAVLINK_MSG_ID_VIBRATION_MIN_LEN 32 @@ -59,13 +59,13 @@ typedef struct __mavlink_vibration_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint * @brief Send a vibration message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field time_usec from vibration message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message /** * @brief Get field vibration_x from vibration message * - * @return Vibration levels on X-axis + * @return Vibration levels on X-axis */ static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_ /** * @brief Get field vibration_y from vibration message * - * @return Vibration levels on Y-axis + * @return Vibration levels on Y-axis */ static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_ /** * @brief Get field vibration_z from vibration message * - * @return Vibration levels on Z-axis + * @return Vibration levels on Z-axis */ static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_ /** * @brief Get field clipping_0 from vibration message * - * @return first accelerometer clipping count + * @return first accelerometer clipping count */ static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_messag /** * @brief Get field clipping_1 from vibration message * - * @return second accelerometer clipping count + * @return second accelerometer clipping count */ static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_messag /** * @brief Get field clipping_2 from vibration message * - * @return third accelerometer clipping count + * @return third accelerometer clipping count */ static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_vicon_position_estimate.h b/lib/main/MAVLink/common/mavlink_msg_vicon_position_estimate.h index 5813b74a64..4ad2a73885 100755 --- a/lib/main/MAVLink/common/mavlink_msg_vicon_position_estimate.h +++ b/lib/main/MAVLink/common/mavlink_msg_vicon_position_estimate.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 -MAVPACKED( + typedef struct __mavlink_vicon_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_vicon_position_estimate_t; + uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/ + float x; /*< [m] Global X position*/ + float y; /*< [m] Global Y position*/ + float z; /*< [m] Global Z position*/ + float roll; /*< [rad] Roll angle*/ + float pitch; /*< [rad] Pitch angle*/ + float yaw; /*< [rad] Yaw angle*/ +} mavlink_vicon_position_estimate_t; #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN 32 @@ -59,13 +59,13 @@ typedef struct __mavlink_vicon_position_estimate_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m] Global X position + * @param y [m] Global Y position + * @param z [m] Global Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m] Global X position + * @param y [m] Global Y position + * @param z [m] Global Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t s * @brief Send a vicon_position_estimate message * @param chan MAVLink channel to send the message * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m] Global X position + * @param y [m] Global Y position + * @param z [m] Global Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_ /** * @brief Get field usec from vicon_position_estimate message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX time or time since system boot) */ static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlin /** * @brief Get field x from vicon_position_estimate message * - * @return Global X position + * @return [m] Global X position */ static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_mess /** * @brief Get field y from vicon_position_estimate message * - * @return Global Y position + * @return [m] Global Y position */ static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_mess /** * @brief Get field z from vicon_position_estimate message * - * @return Global Z position + * @return [m] Global Z position */ static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_mess /** * @brief Get field roll from vicon_position_estimate message * - * @return Roll angle in rad + * @return [rad] Roll angle */ static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_m /** * @brief Get field pitch from vicon_position_estimate message * - * @return Pitch angle in rad + * @return [rad] Pitch angle */ static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_ /** * @brief Get field yaw from vicon_position_estimate message * - * @return Yaw angle in rad + * @return [rad] Yaw angle */ static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_vision_position_estimate.h b/lib/main/MAVLink/common/mavlink_msg_vision_position_estimate.h index 0c351e0845..8c5d5d2e96 100755 --- a/lib/main/MAVLink/common/mavlink_msg_vision_position_estimate.h +++ b/lib/main/MAVLink/common/mavlink_msg_vision_position_estimate.h @@ -3,16 +3,16 @@ #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 -MAVPACKED( + typedef struct __mavlink_vision_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_vision_position_estimate_t; + uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/ + float x; /*< [m] Local X position*/ + float y; /*< [m] Local Y position*/ + float z; /*< [m] Local Z position*/ + float roll; /*< [rad] Roll angle*/ + float pitch; /*< [rad] Pitch angle*/ + float yaw; /*< [rad] Yaw angle*/ +} mavlink_vision_position_estimate_t; #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN 32 @@ -59,13 +59,13 @@ typedef struct __mavlink_vision_position_estimate_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m] Local X position + * @param y [m] Local Y position + * @param z [m] Local Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -105,13 +105,13 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_ * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m] Local X position + * @param y [m] Local Y position + * @param z [m] Local Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -177,13 +177,13 @@ static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t * @brief Send a vision_position_estimate message * @param chan MAVLink channel to send the message * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m] Local X position + * @param y [m] Local Y position + * @param z [m] Local Z position + * @param roll [rad] Roll angle + * @param pitch [rad] Pitch angle + * @param yaw [rad] Yaw angle */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -272,7 +272,7 @@ static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message /** * @brief Get field usec from vision_position_estimate message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX time or time since system boot) */ static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) { @@ -282,7 +282,7 @@ static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavli /** * @brief Get field x from vision_position_estimate message * - * @return Global X position + * @return [m] Local X position */ static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) { @@ -292,7 +292,7 @@ static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_mes /** * @brief Get field y from vision_position_estimate message * - * @return Global Y position + * @return [m] Local Y position */ static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) { @@ -302,7 +302,7 @@ static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_mes /** * @brief Get field z from vision_position_estimate message * - * @return Global Z position + * @return [m] Local Z position */ static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) { @@ -312,7 +312,7 @@ static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_mes /** * @brief Get field roll from vision_position_estimate message * - * @return Roll angle in rad + * @return [rad] Roll angle */ static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) { @@ -322,7 +322,7 @@ static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_ /** * @brief Get field pitch from vision_position_estimate message * - * @return Pitch angle in rad + * @return [rad] Pitch angle */ static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) { @@ -332,7 +332,7 @@ static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink /** * @brief Get field yaw from vision_position_estimate message * - * @return Yaw angle in rad + * @return [rad] Yaw angle */ static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_vision_speed_estimate.h b/lib/main/MAVLink/common/mavlink_msg_vision_speed_estimate.h index bca094713a..b3f3003636 100755 --- a/lib/main/MAVLink/common/mavlink_msg_vision_speed_estimate.h +++ b/lib/main/MAVLink/common/mavlink_msg_vision_speed_estimate.h @@ -3,13 +3,13 @@ #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 -MAVPACKED( + typedef struct __mavlink_vision_speed_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X speed*/ - float y; /*< Global Y speed*/ - float z; /*< Global Z speed*/ -}) mavlink_vision_speed_estimate_t; + uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/ + float x; /*< [m/s] Global X speed*/ + float y; /*< [m/s] Global Y speed*/ + float z; /*< [m/s] Global Z speed*/ +} mavlink_vision_speed_estimate_t; #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN 20 @@ -50,10 +50,10 @@ typedef struct __mavlink_vision_speed_estimate_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m/s] Global X speed + * @param y [m/s] Global Y speed + * @param z [m/s] Global Z speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -87,10 +87,10 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m/s] Global X speed + * @param y [m/s] Global Y speed + * @param z [m/s] Global Z speed * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -150,10 +150,10 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t sys * @brief Send a vision_speed_estimate message * @param chan MAVLink channel to send the message * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed + * @param usec [us] Timestamp (UNIX time or time since system boot) + * @param x [m/s] Global X speed + * @param y [m/s] Global Y speed + * @param z [m/s] Global Z speed */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -230,7 +230,7 @@ static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t /** * @brief Get field usec from vision_speed_estimate message * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) + * @return [us] Timestamp (UNIX time or time since system boot) */ static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) { @@ -240,7 +240,7 @@ static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_ /** * @brief Get field x from vision_speed_estimate message * - * @return Global X speed + * @return [m/s] Global X speed */ static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) { @@ -250,7 +250,7 @@ static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_messag /** * @brief Get field y from vision_speed_estimate message * - * @return Global Y speed + * @return [m/s] Global Y speed */ static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) { @@ -260,7 +260,7 @@ static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_messag /** * @brief Get field z from vision_speed_estimate message * - * @return Global Z speed + * @return [m/s] Global Z speed */ static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/mavlink_msg_wind_cov.h b/lib/main/MAVLink/common/mavlink_msg_wind_cov.h index 0562fb0ea3..abce953e21 100755 --- a/lib/main/MAVLink/common/mavlink_msg_wind_cov.h +++ b/lib/main/MAVLink/common/mavlink_msg_wind_cov.h @@ -3,18 +3,18 @@ #define MAVLINK_MSG_ID_WIND_COV 231 -MAVPACKED( + typedef struct __mavlink_wind_cov_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float wind_x; /*< Wind in X (NED) direction in m/s*/ - float wind_y; /*< Wind in Y (NED) direction in m/s*/ - float wind_z; /*< Wind in Z (NED) direction in m/s*/ - float var_horiz; /*< Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.*/ - float var_vert; /*< Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.*/ - float wind_alt; /*< AMSL altitude (m) this measurement was taken at*/ - float horiz_accuracy; /*< Horizontal speed 1-STD accuracy*/ - float vert_accuracy; /*< Vertical speed 1-STD accuracy*/ -}) mavlink_wind_cov_t; + uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ + float wind_x; /*< [m/s] Wind in X (NED) direction*/ + float wind_y; /*< [m/s] Wind in Y (NED) direction*/ + float wind_z; /*< [m/s] Wind in Z (NED) direction*/ + float var_horiz; /*< [m/s] Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.*/ + float var_vert; /*< [m/s] Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.*/ + float wind_alt; /*< [m] Altitude (MSL) that this measurement was taken at*/ + float horiz_accuracy; /*< [m] Horizontal speed 1-STD accuracy*/ + float vert_accuracy; /*< [m] Vertical speed 1-STD accuracy*/ +} mavlink_wind_cov_t; #define MAVLINK_MSG_ID_WIND_COV_LEN 40 #define MAVLINK_MSG_ID_WIND_COV_MIN_LEN 40 @@ -65,15 +65,15 @@ typedef struct __mavlink_wind_cov_t { * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param wind_x [m/s] Wind in X (NED) direction + * @param wind_y [m/s] Wind in Y (NED) direction + * @param wind_z [m/s] Wind in Z (NED) direction + * @param var_horiz [m/s] Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert [m/s] Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt [m] Altitude (MSL) that this measurement was taken at + * @param horiz_accuracy [m] Horizontal speed 1-STD accuracy + * @param vert_accuracy [m] Vertical speed 1-STD accuracy * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -117,15 +117,15 @@ static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t comp * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param wind_x [m/s] Wind in X (NED) direction + * @param wind_y [m/s] Wind in Y (NED) direction + * @param wind_z [m/s] Wind in Z (NED) direction + * @param var_horiz [m/s] Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert [m/s] Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt [m] Altitude (MSL) that this measurement was taken at + * @param horiz_accuracy [m] Horizontal speed 1-STD accuracy + * @param vert_accuracy [m] Vertical speed 1-STD accuracy * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -195,15 +195,15 @@ static inline uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8 * @brief Send a wind_cov message * @param chan MAVLink channel to send the message * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy + * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. + * @param wind_x [m/s] Wind in X (NED) direction + * @param wind_y [m/s] Wind in Y (NED) direction + * @param wind_z [m/s] Wind in Z (NED) direction + * @param var_horiz [m/s] Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert [m/s] Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt [m] Altitude (MSL) that this measurement was taken at + * @param horiz_accuracy [m] Horizontal speed 1-STD accuracy + * @param vert_accuracy [m] Vertical speed 1-STD accuracy */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -300,7 +300,7 @@ static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf, mavl /** * @brief Get field time_usec from wind_cov message * - * @return Timestamp (micros since boot or Unix epoch) + * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. */ static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t* msg) { @@ -310,7 +310,7 @@ static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_ /** * @brief Get field wind_x from wind_cov message * - * @return Wind in X (NED) direction in m/s + * @return [m/s] Wind in X (NED) direction */ static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg) { @@ -320,7 +320,7 @@ static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg /** * @brief Get field wind_y from wind_cov message * - * @return Wind in Y (NED) direction in m/s + * @return [m/s] Wind in Y (NED) direction */ static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg) { @@ -330,7 +330,7 @@ static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg /** * @brief Get field wind_z from wind_cov message * - * @return Wind in Z (NED) direction in m/s + * @return [m/s] Wind in Z (NED) direction */ static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg) { @@ -340,7 +340,7 @@ static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg /** * @brief Get field var_horiz from wind_cov message * - * @return Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @return [m/s] Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. */ static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* msg) { @@ -350,7 +350,7 @@ static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* /** * @brief Get field var_vert from wind_cov message * - * @return Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @return [m/s] Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. */ static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* msg) { @@ -360,7 +360,7 @@ static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* m /** * @brief Get field wind_alt from wind_cov message * - * @return AMSL altitude (m) this measurement was taken at + * @return [m] Altitude (MSL) that this measurement was taken at */ static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* msg) { @@ -370,7 +370,7 @@ static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* m /** * @brief Get field horiz_accuracy from wind_cov message * - * @return Horizontal speed 1-STD accuracy + * @return [m] Horizontal speed 1-STD accuracy */ static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t* msg) { @@ -380,7 +380,7 @@ static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_messag /** * @brief Get field vert_accuracy from wind_cov message * - * @return Vertical speed 1-STD accuracy + * @return [m] Vertical speed 1-STD accuracy */ static inline float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t* msg) { diff --git a/lib/main/MAVLink/common/testsuite.h b/lib/main/MAVLink/common/testsuite.h index 1952d024a3..a450230f3d 100755 --- a/lib/main/MAVLink/common/testsuite.h +++ b/lib/main/MAVLink/common/testsuite.h @@ -429,6 +429,70 @@ static void mavlink_test_auth_key(uint8_t system_id, uint8_t component_id, mavli MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_link_node_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); + if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LINK_NODE_STATUS >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_link_node_status_t packet_in = { + 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,18691,18795,18899,235,46 + }; + mavlink_link_node_status_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.timestamp = packet_in.timestamp; + packet1.tx_rate = packet_in.tx_rate; + packet1.rx_rate = packet_in.rx_rate; + packet1.messages_sent = packet_in.messages_sent; + packet1.messages_received = packet_in.messages_received; + packet1.messages_lost = packet_in.messages_lost; + packet1.rx_parse_err = packet_in.rx_parse_err; + packet1.tx_overflows = packet_in.tx_overflows; + packet1.rx_overflows = packet_in.rx_overflows; + packet1.tx_buf = packet_in.tx_buf; + packet1.rx_buf = packet_in.rx_buf; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_link_node_status_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_link_node_status_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_link_node_status_pack(system_id, component_id, &msg , packet1.timestamp , packet1.tx_buf , packet1.rx_buf , packet1.tx_rate , packet1.rx_rate , packet1.rx_parse_err , packet1.tx_overflows , packet1.rx_overflows , packet1.messages_sent , packet1.messages_received , packet1.messages_lost ); + mavlink_msg_link_node_status_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_link_node_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.tx_buf , packet1.rx_buf , packet1.tx_rate , packet1.rx_rate , packet1.rx_parse_err , packet1.tx_overflows , packet1.rx_overflows , packet1.messages_sent , packet1.messages_received , packet1.messages_lost ); + mavlink_msg_link_node_status_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_param_ack_transaction_t packet_in = { + 17.0,17,84,"GHIJKLMNOPQRSTU",199,10 + }; + mavlink_param_ack_transaction_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.param_value = packet_in.param_value; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; + packet1.param_type = packet_in.param_type; + packet1.param_result = packet_in.param_result; + + mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_param_ack_transaction_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_param_ack_transaction_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_param_ack_transaction_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_result ); + mavlink_msg_param_ack_transaction_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_param_ack_transaction_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_result ); + mavlink_msg_param_ack_transaction_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CHANGED >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_mission_changed_t packet_in = { + 17235,17339,17,84,151 + }; + mavlink_mission_changed_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.start_index = packet_in.start_index; + packet1.end_index = packet_in.end_index; + packet1.origin_sysid = packet_in.origin_sysid; + packet1.origin_compid = packet_in.origin_compid; + packet1.mission_type = packet_in.mission_type; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CHANGED_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mission_changed_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_mission_changed_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mission_changed_pack(system_id, component_id, &msg , packet1.start_index , packet1.end_index , packet1.origin_sysid , packet1.origin_compid , packet1.mission_type ); + mavlink_msg_mission_changed_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mission_changed_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.start_index , packet1.end_index , packet1.origin_sysid , packet1.origin_compid , packet1.mission_type ); + mavlink_msg_mission_changed_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_CANCEL >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_command_cancel_t packet_in = { + 17235,139,206 + }; + mavlink_command_cancel_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.command = packet_in.command; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_command_cancel_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_command_cancel_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_command_cancel_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command ); + mavlink_msg_command_cancel_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_command_cancel_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command ); + mavlink_msg_command_cancel_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FENCE_STATUS >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_fence_status_t packet_in = { + 963497464,17443,151,218 + }; + mavlink_fence_status_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.breach_time = packet_in.breach_time; + packet1.breach_count = packet_in.breach_count; + packet1.breach_status = packet_in.breach_status; + packet1.breach_type = packet_in.breach_type; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_fence_status_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_fence_status_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_fence_status_pack(system_id, component_id, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time ); + mavlink_msg_fence_status_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_fence_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time ); + mavlink_msg_fence_status_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGH_LATENCY2 >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_high_latency2_t packet_in = { + 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,77,144,211,22,89,156,223,34,101,168,235,46,113,180,247,58,125,192 + }; + mavlink_high_latency2_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.timestamp = packet_in.timestamp; + packet1.latitude = packet_in.latitude; + packet1.longitude = packet_in.longitude; + packet1.custom_mode = packet_in.custom_mode; + packet1.altitude = packet_in.altitude; + packet1.target_altitude = packet_in.target_altitude; + packet1.target_distance = packet_in.target_distance; + packet1.wp_num = packet_in.wp_num; + packet1.failure_flags = packet_in.failure_flags; + packet1.type = packet_in.type; + packet1.autopilot = packet_in.autopilot; + packet1.heading = packet_in.heading; + packet1.target_heading = packet_in.target_heading; + packet1.throttle = packet_in.throttle; + packet1.airspeed = packet_in.airspeed; + packet1.airspeed_sp = packet_in.airspeed_sp; + packet1.groundspeed = packet_in.groundspeed; + packet1.windspeed = packet_in.windspeed; + packet1.wind_heading = packet_in.wind_heading; + packet1.eph = packet_in.eph; + packet1.epv = packet_in.epv; + packet1.temperature_air = packet_in.temperature_air; + packet1.climb_rate = packet_in.climb_rate; + packet1.battery = packet_in.battery; + packet1.custom0 = packet_in.custom0; + packet1.custom1 = packet_in.custom1; + packet1.custom2 = packet_in.custom2; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_high_latency2_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_high_latency2_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_high_latency2_pack(system_id, component_id, &msg , packet1.timestamp , packet1.type , packet1.autopilot , packet1.custom_mode , packet1.latitude , packet1.longitude , packet1.altitude , packet1.target_altitude , packet1.heading , packet1.target_heading , packet1.target_distance , packet1.throttle , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.windspeed , packet1.wind_heading , packet1.eph , packet1.epv , packet1.temperature_air , packet1.climb_rate , packet1.battery , packet1.wp_num , packet1.failure_flags , packet1.custom0 , packet1.custom1 , packet1.custom2 ); + mavlink_msg_high_latency2_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_high_latency2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.type , packet1.autopilot , packet1.custom_mode , packet1.latitude , packet1.longitude , packet1.altitude , packet1.target_altitude , packet1.heading , packet1.target_heading , packet1.target_distance , packet1.throttle , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.windspeed , packet1.wind_heading , packet1.eph , packet1.epv , packet1.temperature_air , packet1.climb_rate , packet1.battery , packet1.wp_num , packet1.failure_flags , packet1.custom0 , packet1.custom1 , packet1.custom2 ); + mavlink_msg_high_latency2_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode */ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, mavlink_status_t* status, @@ -430,17 +409,17 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) * * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *returnMsg and the channel's status is - * copied into *returnStats. + * message is received it is copies into *r_message and the channel's status is + * copied into *r_mavlink_status. * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels + * @param chan ID of the channel to be parsed. + * A channel is not a physical message channel like a serial port, but a logical partition of + * the communication streams. COMM_NB is the limit for the number of channels * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows * @param c The char to parse * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats + * @param r_message NULL if no message could be decoded, the message data else + * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC * * A typical use scenario of this function call is: @@ -448,6 +427,7 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, * @code * #include * + * mavlink_status_t status; * mavlink_message_t msg; * int chan = 0; * @@ -455,7 +435,7 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, * while(serial.bytesAvailable > 0) * { * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * if (mavlink_frame_char(chan, byte, &msg, &status) != MAVLINK_FRAMING_INCOMPLETE) * { * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); * } @@ -480,17 +460,17 @@ MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_messa * it could be successfully decoded. This function will return 0 or 1. * * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *returnMsg and the channel's status is - * copied into *returnStats. + * message is received it is copies into *r_message and the channel's status is + * copied into *r_mavlink_status. * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels + * @param chan ID of the channel to be parsed. + * A channel is not a physical message channel like a serial port, but a logical partition of + * the communication streams. COMM_NB is the limit for the number of channels * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows * @param c The char to parse * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats + * @param r_message NULL if no message could be decoded, otherwise the message data. + * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC * * A typical use scenario of this function call is: @@ -498,6 +478,7 @@ MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_messa * @code * #include * + * mavlink_status_t status; * mavlink_message_t msg; * int chan = 0; * @@ -505,7 +486,7 @@ MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_messa * while(serial.bytesAvailable > 0) * { * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) + * if (mavlink_parse_char(chan, byte, &msg, &status)) * { * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); * } diff --git a/lib/main/MAVLink/protocol.h b/lib/main/MAVLink/protocol.h index 731bd3a583..34749d9ba7 100755 --- a/lib/main/MAVLink/protocol.h +++ b/lib/main/MAVLink/protocol.h @@ -239,9 +239,9 @@ _MAV_PUT_ARRAY(int64_t, i64) _MAV_PUT_ARRAY(float, f) _MAV_PUT_ARRAY(double, d) -#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_char(msg, wire_offset) (char)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset] #if MAVLINK_NEED_BYTE_SWAP #define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \