From 1e4f463298530a4b77477513512712550d37a7b4 Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Fri, 5 Aug 2011 08:18:08 +0000 Subject: [PATCH] Updated GCS_MAVLink to match mavlink master. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3017 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- .../include/ardupilotmega/ardupilotmega.h | 6 +- .../include/ardupilotmega/mavlink.h | 2 +- libraries/GCS_MAVLink/include/common/common.h | 100 +- .../GCS_MAVLink/include/common/mavlink.h | 2 +- .../include/common/mavlink_msg_full_state.h | 428 ++++ .../common/mavlink_msg_set_roll_pitch_yaw.h | 184 ++ .../mavlink_msg_set_roll_pitch_yaw_speed.h | 184 ++ libraries/GCS_MAVLink/include/mavlink_types.h | 31 +- .../GCS_MAVLink/include/minimal/mavlink.h | 11 + .../include/minimal/mavlink_msg_heartbeat.h | 132 ++ .../GCS_MAVLink/include/minimal/minimal.h | 45 + .../GCS_MAVLink/include/pixhawk/mavlink.h | 2 +- .../pixhawk/mavlink_msg_image_available.h | 76 +- .../pixhawk/mavlink_msg_image_triggered.h | 76 +- .../mavlink_msg_vision_speed_estimate.h | 176 ++ .../GCS_MAVLink/include/pixhawk/pixhawk.h | 18 +- libraries/GCS_MAVLink/include/protocol.h | 2 +- libraries/GCS_MAVLink/include/slugs/mavlink.h | 2 +- libraries/GCS_MAVLink/include/slugs/slugs.h | 6 +- .../GCS_MAVLink/include/ualberta/mavlink.h | 2 +- .../ualberta/mavlink_msg_radio_calibration.h | 104 +- .../mavlink_msg_ualberta_sys_status.h | 135 ++ .../GCS_MAVLink/include/ualberta/ualberta.h | 38 +- .../message_definitions/ardupilotmega.xml | 6 +- .../message_definitions/common.xml | 1824 +++++++++-------- .../message_definitions/minimal.xml | 13 + .../message_definitions/pixhawk.xml | 511 ++--- .../GCS_MAVLink/message_definitions/slugs.xml | 220 +- .../message_definitions/ualberta.xml | 79 +- .../GCS_MAVLink/missionlib/testing/.gitignore | 3 + .../GCS_MAVLink/missionlib/testing/Makefile | 12 + .../GCS_MAVLink/missionlib/testing/main.c | 255 +++ .../GCS_MAVLink/missionlib/testing/udp.c | 1073 ++++++++++ .../GCS_MAVLink/missionlib/testing/udptest.1 | 79 + .../testing/udptest.xcodeproj/project.pbxproj | 211 ++ .../testing/udptest.xcodeproj/user.mode1v3 | 1440 +++++++++++++ .../testing/udptest.xcodeproj/user.pbxuser | 236 +++ libraries/GCS_MAVLink/missionlib/waypoints.c | 880 ++++++++ libraries/GCS_MAVLink/missionlib/waypoints.h | 91 + libraries/GCS_MAVLink/sync | 5 +- 40 files changed, 7258 insertions(+), 1442 deletions(-) create mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h create mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h create mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h create mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink.h create mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h create mode 100644 libraries/GCS_MAVLink/include/minimal/minimal.h create mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_vision_speed_estimate.h create mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h create mode 100644 libraries/GCS_MAVLink/message_definitions/minimal.xml create mode 100644 libraries/GCS_MAVLink/missionlib/testing/.gitignore create mode 100644 libraries/GCS_MAVLink/missionlib/testing/Makefile create mode 100644 libraries/GCS_MAVLink/missionlib/testing/main.c create mode 100644 libraries/GCS_MAVLink/missionlib/testing/udp.c create mode 100644 libraries/GCS_MAVLink/missionlib/testing/udptest.1 create mode 100644 libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/project.pbxproj create mode 100644 libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.mode1v3 create mode 100644 libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.pbxuser create mode 100644 libraries/GCS_MAVLink/missionlib/waypoints.c create mode 100644 libraries/GCS_MAVLink/missionlib/waypoints.h diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h index e002077c4f..a82d854a7f 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. - * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:01 UTC + * @see http://qgroundcontrol.org/mavlink/ + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef ARDUPILOTMEGA_H #define ARDUPILOTMEGA_H @@ -38,7 +38,7 @@ extern "C" { // MESSAGE LENGTHS #undef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 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, 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, 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, 30, 14, 14, 51 } +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 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, 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, 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, 30, 14, 14, 51 } #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h index b9f073a07d..486083900b 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:01 UTC + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/common/common.h b/libraries/GCS_MAVLink/include/common/common.h index 17299dfcfa..d6168006e8 100644 --- a/libraries/GCS_MAVLink/include/common/common.h +++ b/libraries/GCS_MAVLink/include/common/common.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. - * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Wednesday, May 18 2011, 03:15 UTC + * @see http://qgroundcontrol.org/mavlink/ + * Generated on Friday, August 5 2011, 08:13 UTC */ #ifndef COMMON_H #define COMMON_H @@ -28,63 +28,64 @@ extern "C" { // ENUM DEFINITIONS -/** @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 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. */ enum MAV_CMD { - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint.Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)Acceptance radius in meters (if the sphere with this radius is hit, the waypoint 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 waypoint (rotary wing)LatitudeLongitudeAltitude*/ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of timeEmptyEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turnsTurnsEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X secondsSeconds (decimal)EmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch locationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_NAV_LAND=21, /* Land at locationEmptyEmptyEmptyDesired yaw angle.LatitudeLongitudeAltitude*/ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / handMinimum pitch (if airspeed sensor present), desired pitch without sensorEmptyEmptyYaw angle (if magnetometer present), ignored without magnetometerLatitudeLongitudeAltitude*/ - 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 planning0: 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 gridEmptyYaw angle at goal, in compass degrees, [0..360]Latitude/X of goalLongitude/Y of goalAltitude/Z of goal*/ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine.Delay in seconds (decimal)EmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached.Descent / Ascend rate (m/s)EmptyEmptyEmptyEmptyEmptyFinish Altitude*/ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point.Distance (meters)EmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle.target angle: [0-360], 0 is northspeed during yaw change:[deg per second]direction: negative: counter clockwise, positive: clockwise [-1,1]relative offset or absolute angle: [ 1,0]EmptyEmptyEmpty*/ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_DO_SET_MODE=176, /* Set system mode.Mode, as defined by ENUM MAV_MODEEmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of timesSequence numberRepeat countEmptyEmptyEmptyEmptyEmpty*/ - 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)EmptyEmptyEmptyEmpty*/ - 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)EmptyEmptyEmptyLatitudeLongitudeAltitude*/ - 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 numberParameter valueEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition.Relay numberSetting (1=on, 0=off, others possible depending on system hardware)EmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period.Relay numberCycle countCycle time (seconds, decimal)EmptyEmptyEmptyEmpty*/ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value.Servo numberPWM (microseconds, 1000 to 2000 typical)EmptyEmptyEmptyEmptyEmpty*/ - 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 numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system.Camera ID (-1 for all)Transmission: 0: disabled, 1: enabled compressed, 2: enabled rawTransmission mode: 0: video stream, >0: single images every n seconds (decimal)Recording: 0: disabled, 1: enabled compressed, 2: enabled rawEmptyEmptyEmpty*/ - 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 devices such as cameras.Region of interest mode. (see MAV_ROI enum)Waypoint index/ target ID. (see MAV_ROI enum)ROI index (allows a vehicle to manage multiple cameras etc.)Emptyx the location of the fixed ROI (see MAV_FRAME)yz*/ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode.Gyro calibration: 0: no, 1: yesMagnetometer calibration: 0: no, 1: yesGround pressure: 0: no, 1: yesRadio calibration: 0: no, 1: yesEmptyEmptyEmpty*/ - 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/EEPROMMission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMReservedReservedEmptyEmptyEmpty*/ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. | Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) | Acceptance radius in meters (if the sphere with this radius is hit, the waypoint 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 waypoint (rotary wing) | Latitude | Longitude | Altitude | */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time | Empty | Empty | Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns | Turns | Empty | Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | Latitude | Longitude | Altitude | */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X seconds | Seconds (decimal) | Empty | Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise | Desired yaw angle. | 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 | Empty | 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_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) | 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, in compass degrees, [0..360] | Latitude/X of goal | Longitude/Y of goal | Altitude/Z of goal | */ + 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_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 | Empty | Empty | 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) | Empty | 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_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_CONTROL_VIDEO=200, /* Control onboard camera capturing. | 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 devices such as cameras. | Region of interest mode. (see MAV_ROI enum) | Waypoint index/ target ID. (see MAV_ROI enum) | ROI index (allows a vehicle to manage multiple cameras etc.) | Empty | x the location of the fixed ROI (see MAV_FRAME) | y | z | */ + 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. | Gyro calibration: 0: no, 1: yes | Magnetometer calibration: 0: no, 1: yes | Ground pressure: 0: no, 1: yes | Radio calibration: 0: no, 1: yes | Empty | Empty | Empty | */ + 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 | Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Reserved | Reserved | Empty | Empty | Empty | */ MAV_CMD_ENUM_END }; -/** @brief Data stream IDs. 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. */ +/** @brief Data stream IDs. 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. */ enum MAV_DATA_STREAM { - MAV_DATA_STREAM_ALL=0, /* Enable all data streams*/ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.*/ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS*/ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW*/ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.*/ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.*/ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot*/ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot*/ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot*/ + MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ + MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ + MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ + MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ + MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ + MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ + MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ MAV_DATA_STREAM_ENUM_END }; -/** @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_DO_SET_ROI). */ +/** @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). */ enum MAV_ROI { - MAV_ROI_NONE=0, /* No region of interest.*/ - MAV_ROI_WPNEXT=1, /* Point toward next waypoint.*/ - MAV_ROI_WPINDEX=2, /* Point toward given waypoint.*/ - MAV_ROI_LOCATION=3, /* Point toward fixed location.*/ - MAV_ROI_TARGET=4, /* Point toward target of given id.*/ + MAV_ROI_NONE=0, /* No region of interest. | */ + MAV_ROI_WPNEXT=1, /* Point toward next waypoint. | */ + 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 }; @@ -137,6 +138,8 @@ enum MAV_ROI #include "./mavlink_msg_control_status.h" #include "./mavlink_msg_safety_set_allowed_area.h" #include "./mavlink_msg_safety_allowed_area.h" +#include "./mavlink_msg_set_roll_pitch_yaw.h" +#include "./mavlink_msg_set_roll_pitch_yaw_speed.h" #include "./mavlink_msg_attitude_controller_output.h" #include "./mavlink_msg_position_controller_output.h" #include "./mavlink_msg_nav_controller_output.h" @@ -144,6 +147,7 @@ enum MAV_ROI #include "./mavlink_msg_state_correction.h" #include "./mavlink_msg_set_altitude.h" #include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_full_state.h" #include "./mavlink_msg_manual_control.h" #include "./mavlink_msg_rc_channels_override.h" #include "./mavlink_msg_global_position_int.h" @@ -160,7 +164,7 @@ enum MAV_ROI // MESSAGE LENGTHS #undef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 18, 0, 0, 18, 20, 20, 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, 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, 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, 30, 14, 14, 51 } +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 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, 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, 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, 30, 14, 14, 51 } #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/include/common/mavlink.h b/libraries/GCS_MAVLink/include/common/mavlink.h index 17e6bf084a..2d1f4c6f65 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink.h +++ b/libraries/GCS_MAVLink/include/common/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Wednesday, May 18 2011, 03:15 UTC + * Generated on Friday, August 5 2011, 08:13 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h new file mode 100644 index 0000000000..ed177e22e2 --- /dev/null +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h @@ -0,0 +1,428 @@ +// MESSAGE FULL_STATE PACKING + +#define MAVLINK_MSG_ID_FULL_STATE 67 + +typedef struct __mavlink_full_state_t +{ + uint64_t 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; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw 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_full_state_t; + + + +/** + * @brief Pack a full_state 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 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 Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw 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) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_full_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_FULL_STATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad) + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad) + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad) + i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s) + i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s) + i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s) + i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7 + i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7 + i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters) + i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100 + i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100 + i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100 + i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg) + i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg) + i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a full_state message + * @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 was sent over + * @param msg The MAVLink message to compress the data into + * @param 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 Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw 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) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_full_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_FULL_STATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad) + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad) + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad) + i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s) + i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s) + i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s) + i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7 + i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7 + i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters) + i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100 + i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100 + i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100 + i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg) + i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg) + i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a full_state struct into a 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 full_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_full_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_full_state_t* full_state) +{ + return mavlink_msg_full_state_pack(system_id, component_id, msg, full_state->usec, full_state->roll, full_state->pitch, full_state->yaw, full_state->rollspeed, full_state->pitchspeed, full_state->yawspeed, full_state->lat, full_state->lon, full_state->alt, full_state->vx, full_state->vy, full_state->vz, full_state->xacc, full_state->yacc, full_state->zacc); +} + +/** + * @brief Send a full_state message + * @param chan MAVLink channel to send the message + * + * @param 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 Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw 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) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_full_state_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ + mavlink_message_t msg; + mavlink_msg_full_state_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE FULL_STATE UNPACKING + +/** + * @brief Get field usec from full_state message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_full_state_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field roll from full_state message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_full_state_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from full_state message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_full_state_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from full_state message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_full_state_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field rollspeed from full_state message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_full_state_get_rollspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitchspeed from full_state message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_full_state_get_pitchspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yawspeed from full_state message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_full_state_get_yawspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field lat from full_state message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_full_state_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field lon from full_state message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_full_state_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field alt from full_state message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_full_state_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field vx from full_state message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_full_state_get_vx(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field vy from full_state message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_full_state_get_vy(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field vz from full_state message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_full_state_get_vz(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field xacc from full_state message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_full_state_get_xacc(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field yacc from full_state message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_full_state_get_yacc(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zacc from full_state message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_full_state_get_zacc(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a full_state message into a struct + * + * @param msg The message to decode + * @param full_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_full_state_decode(const mavlink_message_t* msg, mavlink_full_state_t* full_state) +{ + full_state->usec = mavlink_msg_full_state_get_usec(msg); + full_state->roll = mavlink_msg_full_state_get_roll(msg); + full_state->pitch = mavlink_msg_full_state_get_pitch(msg); + full_state->yaw = mavlink_msg_full_state_get_yaw(msg); + full_state->rollspeed = mavlink_msg_full_state_get_rollspeed(msg); + full_state->pitchspeed = mavlink_msg_full_state_get_pitchspeed(msg); + full_state->yawspeed = mavlink_msg_full_state_get_yawspeed(msg); + full_state->lat = mavlink_msg_full_state_get_lat(msg); + full_state->lon = mavlink_msg_full_state_get_lon(msg); + full_state->alt = mavlink_msg_full_state_get_alt(msg); + full_state->vx = mavlink_msg_full_state_get_vx(msg); + full_state->vy = mavlink_msg_full_state_get_vy(msg); + full_state->vz = mavlink_msg_full_state_get_vz(msg); + full_state->xacc = mavlink_msg_full_state_get_xacc(msg); + full_state->yacc = mavlink_msg_full_state_get_yacc(msg); + full_state->zacc = mavlink_msg_full_state_get_zacc(msg); +} diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h new file mode 100644 index 0000000000..1cc68dff92 --- /dev/null +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h @@ -0,0 +1,184 @@ +// MESSAGE SET_ROLL_PITCH_YAW PACKING + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW 55 + +typedef struct __mavlink_set_roll_pitch_yaw_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float roll; ///< Desired roll angle in radians + float pitch; ///< Desired pitch angle in radians + float yaw; ///< Desired yaw angle in radians + +} mavlink_set_roll_pitch_yaw_t; + + + +/** + * @brief Pack a set_roll_pitch_yaw 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 ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID + i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians + i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians + i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a set_roll_pitch_yaw message + * @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 was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_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, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID + i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians + i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians + i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a set_roll_pitch_yaw struct into a 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 set_roll_pitch_yaw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_t* set_roll_pitch_yaw) +{ + return mavlink_msg_set_roll_pitch_yaw_pack(system_id, component_id, msg, set_roll_pitch_yaw->target_system, set_roll_pitch_yaw->target_component, set_roll_pitch_yaw->roll, set_roll_pitch_yaw->pitch, set_roll_pitch_yaw->yaw); +} + +/** + * @brief Send a set_roll_pitch_yaw message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_roll_pitch_yaw_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_set_roll_pitch_yaw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_ROLL_PITCH_YAW UNPACKING + +/** + * @brief Get field target_system from set_roll_pitch_yaw message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from set_roll_pitch_yaw message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field roll from set_roll_pitch_yaw message + * + * @return Desired roll angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from set_roll_pitch_yaw message + * + * @return Desired pitch angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from set_roll_pitch_yaw message + * + * @return Desired yaw angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a set_roll_pitch_yaw message into a struct + * + * @param msg The message to decode + * @param set_roll_pitch_yaw C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_roll_pitch_yaw_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_t* set_roll_pitch_yaw) +{ + set_roll_pitch_yaw->target_system = mavlink_msg_set_roll_pitch_yaw_get_target_system(msg); + set_roll_pitch_yaw->target_component = mavlink_msg_set_roll_pitch_yaw_get_target_component(msg); + set_roll_pitch_yaw->roll = mavlink_msg_set_roll_pitch_yaw_get_roll(msg); + set_roll_pitch_yaw->pitch = mavlink_msg_set_roll_pitch_yaw_get_pitch(msg); + set_roll_pitch_yaw->yaw = mavlink_msg_set_roll_pitch_yaw_get_yaw(msg); +} diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h new file mode 100644 index 0000000000..7855daf765 --- /dev/null +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h @@ -0,0 +1,184 @@ +// MESSAGE SET_ROLL_PITCH_YAW_SPEED PACKING + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED 56 + +typedef struct __mavlink_set_roll_pitch_yaw_speed_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float roll_speed; ///< Desired roll angular speed in rad/s + float pitch_speed; ///< Desired pitch angular speed in rad/s + float yaw_speed; ///< Desired yaw angular speed in rad/s + +} mavlink_set_roll_pitch_yaw_speed_t; + + + +/** + * @brief Pack a set_roll_pitch_yaw_speed 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 ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID + i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s + i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s + i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a set_roll_pitch_yaw_speed message + * @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 was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_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, float roll_speed, float pitch_speed, float yaw_speed) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID + i += put_float_by_index(roll_speed, i, msg->payload); // Desired roll angular speed in rad/s + i += put_float_by_index(pitch_speed, i, msg->payload); // Desired pitch angular speed in rad/s + i += put_float_by_index(yaw_speed, i, msg->payload); // Desired yaw angular speed in rad/s + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a set_roll_pitch_yaw_speed struct into a 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 set_roll_pitch_yaw_speed C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_t* set_roll_pitch_yaw_speed) +{ + return mavlink_msg_set_roll_pitch_yaw_speed_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed->target_system, set_roll_pitch_yaw_speed->target_component, set_roll_pitch_yaw_speed->roll_speed, set_roll_pitch_yaw_speed->pitch_speed, set_roll_pitch_yaw_speed->yaw_speed); +} + +/** + * @brief Send a set_roll_pitch_yaw_speed message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_roll_pitch_yaw_speed_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed) +{ + mavlink_message_t msg; + mavlink_msg_set_roll_pitch_yaw_speed_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll_speed, pitch_speed, yaw_speed); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_ROLL_PITCH_YAW_SPEED UNPACKING + +/** + * @brief Get field target_system from set_roll_pitch_yaw_speed message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from set_roll_pitch_yaw_speed message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field roll_speed from set_roll_pitch_yaw_speed message + * + * @return Desired roll angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_get_roll_speed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch_speed from set_roll_pitch_yaw_speed message + * + * @return Desired pitch angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_get_pitch_speed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw_speed from set_roll_pitch_yaw_speed message + * + * @return Desired yaw angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_get_yaw_speed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a set_roll_pitch_yaw_speed message into a struct + * + * @param msg The message to decode + * @param set_roll_pitch_yaw_speed C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_roll_pitch_yaw_speed_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_t* set_roll_pitch_yaw_speed) +{ + set_roll_pitch_yaw_speed->target_system = mavlink_msg_set_roll_pitch_yaw_speed_get_target_system(msg); + set_roll_pitch_yaw_speed->target_component = mavlink_msg_set_roll_pitch_yaw_speed_get_target_component(msg); + set_roll_pitch_yaw_speed->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_get_roll_speed(msg); + set_roll_pitch_yaw_speed->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_get_pitch_speed(msg); + set_roll_pitch_yaw_speed->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_get_yaw_speed(msg); +} diff --git a/libraries/GCS_MAVLink/include/mavlink_types.h b/libraries/GCS_MAVLink/include/mavlink_types.h index 2eff48ef8f..67eed17c8e 100644 --- a/libraries/GCS_MAVLink/include/mavlink_types.h +++ b/libraries/GCS_MAVLink/include/mavlink_types.h @@ -13,6 +13,7 @@ enum MAV_CLASS MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set + MAV_CLASS_NONE = 8, ///< No valid autopilot MAV_CLASS_NB ///< Number of autopilot classes }; @@ -101,7 +102,8 @@ enum MAV_NAV MAV_NAV_RETURNING, MAV_NAV_LANDING, MAV_NAV_LOST, - MAV_NAV_LOITER + MAV_NAV_LOITER, + MAV_NAV_FREE_DRIFT }; enum MAV_TYPE @@ -112,7 +114,12 @@ enum MAV_TYPE MAV_COAXIAL = 3, MAV_HELICOPTER = 4, MAV_GROUND = 5, - OCU = 6 + OCU = 6, + MAV_AIRSHIP = 7, + MAV_FREE_BALLOON = 8, + MAV_ROCKET = 9, + UGV_GROUND_ROVER = 10, + UGV_SURFACE_SHIP = 11 }; enum MAV_AUTOPILOT_TYPE @@ -120,7 +127,8 @@ enum MAV_AUTOPILOT_TYPE MAV_AUTOPILOT_GENERIC = 0, MAV_AUTOPILOT_PIXHAWK = 1, MAV_AUTOPILOT_SLUGS = 2, - MAV_AUTOPILOT_ARDUPILOTMEGA = 3 + MAV_AUTOPILOT_ARDUPILOTMEGA = 3, + MAV_AUTOPILOT_NONE = 4 }; enum MAV_COMPONENT @@ -133,6 +141,8 @@ enum MAV_COMPONENT MAV_COMP_ID_MAPPER, MAV_COMP_ID_CAMERA, MAV_COMP_ID_IMU = 200, + MAV_COMP_ID_IMU_2 = 201, + MAV_COMP_ID_IMU_3 = 202, MAV_COMP_ID_UDP_BRIDGE = 240, MAV_COMP_ID_UART_BRIDGE = 241, MAV_COMP_ID_SYSTEM_CONTROL = 250 @@ -143,7 +153,19 @@ enum MAV_FRAME MAV_FRAME_GLOBAL = 0, MAV_FRAME_LOCAL = 1, MAV_FRAME_MISSION = 2, - MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 + MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, + MAV_FRAME_LOCAL_ENU = 4 +}; + +enum MAVLINK_DATA_STREAM_TYPE +{ + MAVLINK_DATA_STREAM_IMG_JPEG, + MAVLINK_DATA_STREAM_IMG_BMP, + MAVLINK_DATA_STREAM_IMG_RAW8U, + MAVLINK_DATA_STREAM_IMG_RAW32U, + MAVLINK_DATA_STREAM_IMG_PGM, + MAVLINK_DATA_STREAM_IMG_PNG + }; #define MAVLINK_STX 0x55 ///< Packet start sign @@ -165,6 +187,7 @@ typedef struct __mavlink_system { uint8_t type; ///< Unused, can be used by user to store the system's type uint8_t state; ///< Unused, can be used by user to store the system's state uint8_t mode; ///< Unused, can be used by user to store the system's mode + uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode } mavlink_system_t; typedef struct __mavlink_message { diff --git a/libraries/GCS_MAVLink/include/minimal/mavlink.h b/libraries/GCS_MAVLink/include/minimal/mavlink.h new file mode 100644 index 0000000000..38389146ab --- /dev/null +++ b/libraries/GCS_MAVLink/include/minimal/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Friday, August 5 2011, 07:37 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "minimal.h" + +#endif diff --git a/libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h b/libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h new file mode 100644 index 0000000000..0e5c4db5ca --- /dev/null +++ b/libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h @@ -0,0 +1,132 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + uint8_t mavlink_version; ///< MAVLink version + +} mavlink_heartbeat_t; + + + +/** + * @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + * @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, uint8_t type, uint8_t autopilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + + i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a heartbeat message + * @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 was 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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + * @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, mavlink_message_t* msg, uint8_t type, uint8_t autopilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + + i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a heartbeat struct into a 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 heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot); +} + +/** + * @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 Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot) +{ + mavlink_message_t msg; + mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE HEARTBEAT UNPACKING + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +} diff --git a/libraries/GCS_MAVLink/include/minimal/minimal.h b/libraries/GCS_MAVLink/include/minimal/minimal.h new file mode 100644 index 0000000000..ee09135a68 --- /dev/null +++ b/libraries/GCS_MAVLink/include/minimal/minimal.h @@ -0,0 +1,45 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://qgroundcontrol.org/mavlink/ + * Generated on Friday, August 5 2011, 07:37 UTC + */ +#ifndef MINIMAL_H +#define MINIMAL_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_MINIMAL + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + +// MESSAGE DEFINITIONS + +#include "./mavlink_msg_heartbeat.h" + + +// MESSAGE LENGTHS + +#undef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS { } + +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/GCS_MAVLink/include/pixhawk/mavlink.h b/libraries/GCS_MAVLink/include/pixhawk/mavlink.h index 6a5785af15..7d19e1ba6a 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/mavlink.h +++ b/libraries/GCS_MAVLink/include/pixhawk/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:02 UTC + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h b/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h index 472449988b..b40e23df7b 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h +++ b/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h @@ -24,6 +24,9 @@ typedef struct __mavlink_image_available_t float lat; ///< GPS X coordinate float lon; ///< GPS Y coordinate float alt; ///< Global frame altitude + float ground_x; ///< Ground truth X + float ground_y; ///< Ground truth Y + float ground_z; ///< Ground truth Z } mavlink_image_available_t; @@ -55,9 +58,12 @@ typedef struct __mavlink_image_available_t * @param lat GPS X coordinate * @param lon GPS Y coordinate * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; @@ -82,6 +88,9 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X + i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y + i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z return mavlink_finalize_message(msg, system_id, component_id, i); } @@ -112,9 +121,12 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 * @param lat GPS X coordinate * @param lon GPS Y coordinate * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; @@ -139,6 +151,9 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X + i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y + i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } @@ -153,7 +168,7 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, */ static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available) { - return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt); + return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z); } /** @@ -180,13 +195,16 @@ static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uin * @param lat GPS X coordinate * @param lon GPS Y coordinate * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) { mavlink_message_t msg; - mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch, yaw, local_z, lat, lon, alt); + mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z); mavlink_send_uart(chan, &msg); } @@ -489,6 +507,51 @@ static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* return (float)r.f; } +/** + * @brief Get field ground_x from image_available message + * + * @return Ground truth X + */ +static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field ground_y from image_available message + * + * @return Ground truth Y + */ +static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field ground_z from image_available message + * + * @return Ground truth Z + */ +static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + /** * @brief Decode a image_available message into a struct * @@ -517,4 +580,7 @@ static inline void mavlink_msg_image_available_decode(const mavlink_message_t* m image_available->lat = mavlink_msg_image_available_get_lat(msg); image_available->lon = mavlink_msg_image_available_get_lon(msg); image_available->alt = mavlink_msg_image_available_get_alt(msg); + image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg); + image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg); + image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg); } diff --git a/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h b/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h index 01f8a9203e..000003f3d7 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h +++ b/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h @@ -13,6 +13,9 @@ typedef struct __mavlink_image_triggered_t float lat; ///< GPS X coordinate float lon; ///< GPS Y coordinate float alt; ///< Global frame altitude + float ground_x; ///< Ground truth X + float ground_y; ///< Ground truth Y + float ground_z; ///< Ground truth Z } mavlink_image_triggered_t; @@ -33,9 +36,12 @@ typedef struct __mavlink_image_triggered_t * @param lat GPS X coordinate * @param lon GPS Y coordinate * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; @@ -49,6 +55,9 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X + i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y + i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z return mavlink_finalize_message(msg, system_id, component_id, i); } @@ -68,9 +77,12 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 * @param lat GPS X coordinate * @param lon GPS Y coordinate * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; @@ -84,6 +96,9 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X + i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y + i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } @@ -98,7 +113,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, */ static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) { - return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt); + return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z); } /** @@ -114,13 +129,16 @@ static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uin * @param lat GPS X coordinate * @param lon GPS Y coordinate * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) { mavlink_message_t msg; - mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt); + mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z); mavlink_send_uart(chan, &msg); } @@ -266,6 +284,51 @@ static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* return (float)r.f; } +/** + * @brief Get field ground_x from image_triggered message + * + * @return Ground truth X + */ +static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field ground_y from image_triggered message + * + * @return Ground truth Y + */ +static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field ground_z from image_triggered message + * + * @return Ground truth Z + */ +static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + /** * @brief Decode a image_triggered message into a struct * @@ -283,4 +346,7 @@ static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* m image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg); image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg); image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg); + image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg); + image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg); + image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg); } diff --git a/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_vision_speed_estimate.h b/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_vision_speed_estimate.h new file mode 100644 index 0000000000..66224c28e9 --- /dev/null +++ b/libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_vision_speed_estimate.h @@ -0,0 +1,176 @@ +// MESSAGE VISION_SPEED_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 113 + +typedef struct __mavlink_vision_speed_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X speed + float y; ///< Global Y speed + float z; ///< Global Z speed + +} mavlink_vision_speed_estimate_t; + + + +/** + * @brief Pack a vision_speed_estimate 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 usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z 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, uint64_t usec, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); // Global X speed + i += put_float_by_index(y, i, msg->payload); // Global Y speed + i += put_float_by_index(z, i, msg->payload); // Global Z speed + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a vision_speed_estimate message + * @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 was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z 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, mavlink_message_t* msg, uint64_t usec, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); // Global X speed + i += put_float_by_index(y, i, msg->payload); // Global Y speed + i += put_float_by_index(z, i, msg->payload); // Global Z speed + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a vision_speed_estimate struct into a 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 vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Send a vision_speed_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ + mavlink_message_t msg; + mavlink_msg_vision_speed_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE VISION_SPEED_ESTIMATE UNPACKING + +/** + * @brief Get field usec from vision_speed_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from vision_speed_estimate message + * + * @return Global X speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from vision_speed_estimate message + * + * @return Global Y speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from vision_speed_estimate message + * + * @return Global Z speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a vision_speed_estimate message into a struct + * + * @param msg The message to decode + * @param vision_speed_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); + vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); + vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); + vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); +} diff --git a/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h b/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h index 08f466fd2d..318877e873 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h +++ b/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. - * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:02 UTC + * @see http://qgroundcontrol.org/mavlink/ + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef PIXHAWK_H #define PIXHAWK_H @@ -30,16 +30,7 @@ extern "C" { // ENUM DEFINITIONS -/** @brief Slugs parameter interface subsets */ -enum SLUGS_PID_INDX_IDS -{ - PID_YAW_DAMPER=2, - PID_PITCH=3, /* With comment: PID Pitch parameter*/ - PID_ALT_HOLD=50, - SLUGS_PID_INDX_IDS_ENUM_END -}; - -/** @brief Content Types for data transmission handshake */ +/** @brief Content Types for data transmission handshake */ enum DATA_TYPES { DATA_TYPE_JPEG_IMAGE=1, @@ -58,6 +49,7 @@ enum DATA_TYPES #include "./mavlink_msg_image_available.h" #include "./mavlink_msg_vision_position_estimate.h" #include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_vision_speed_estimate.h" #include "./mavlink_msg_position_control_setpoint_set.h" #include "./mavlink_msg_position_control_offset_set.h" #include "./mavlink_msg_position_control_setpoint.h" @@ -79,7 +71,7 @@ enum DATA_TYPES // MESSAGE LENGTHS #undef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 40, 1, 80, 0, 0, 0, 0, 0, 0, 0, 32, 32, 0, 0, 0, 0, 0, 0, 0, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 12, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 18, 0, 0, 0, 0, 0, 106, 42, 54, 0, 0, 0, 0, 0, 0, 0, 8, 255, 53, 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, 30, 14, 14, 51 } +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 0, 0, 32, 32, 20, 0, 0, 0, 0, 0, 0, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 12, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 18, 0, 0, 0, 0, 0, 106, 42, 54, 0, 0, 0, 0, 0, 0, 0, 8, 255, 53, 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, 30, 14, 14, 51 } #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/include/protocol.h b/libraries/GCS_MAVLink/include/protocol.h index aea2616019..ed1f9546b4 100644 --- a/libraries/GCS_MAVLink/include/protocol.h +++ b/libraries/GCS_MAVLink/include/protocol.h @@ -805,7 +805,7 @@ static inline uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t p // First pack everything we can into the current 'open' byte //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 //FIXME - if (bits_remain <= (unsigned)(8 - i_bit_index)) + if (bits_remain <= (8 - i_bit_index)) { // Enough space curr_bits_n = bits_remain; diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink.h b/libraries/GCS_MAVLink/include/slugs/mavlink.h index d456a6bc56..29ce7ed555 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:02 UTC + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/slugs/slugs.h b/libraries/GCS_MAVLink/include/slugs/slugs.h index 84bc1405f4..b04cb7922f 100644 --- a/libraries/GCS_MAVLink/include/slugs/slugs.h +++ b/libraries/GCS_MAVLink/include/slugs/slugs.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. - * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:02 UTC + * @see http://qgroundcontrol.org/mavlink/ + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef SLUGS_H #define SLUGS_H @@ -48,7 +48,7 @@ extern "C" { // MESSAGE LENGTHS #undef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 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, 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, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 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, 30, 14, 14, 51 } +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 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, 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, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 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, 30, 14, 14, 51 } #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/include/ualberta/mavlink.h b/libraries/GCS_MAVLink/include/ualberta/mavlink.h index 172cc2857a..e12f74a8df 100644 --- a/libraries/GCS_MAVLink/include/ualberta/mavlink.h +++ b/libraries/GCS_MAVLink/include/ualberta/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:02 UTC + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h b/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h index 7a599ac714..5907aba95b 100644 --- a/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h +++ b/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h @@ -1,15 +1,15 @@ // MESSAGE RADIO_CALIBRATION PACKING -#define MAVLINK_MSG_ID_RADIO_CALIBRATION 222 +#define MAVLINK_MSG_ID_RADIO_CALIBRATION 221 typedef struct __mavlink_radio_calibration_t { - float aileron[3]; ///< Aileron setpoints: high, center, low - float elevator[3]; ///< Elevator setpoints: high, center, low - float rudder[3]; ///< Rudder setpoints: high, center, low - float gyro[2]; ///< Tail gyro mode/gain setpoints: heading hold, rate mode - float pitch[5]; ///< Pitch curve setpoints (every 25%) - float throttle[5]; ///< Throttle curve setpoints (every 25%) + uint16_t aileron[3]; ///< Aileron setpoints: left, center, right + uint16_t elevator[3]; ///< Elevator setpoints: nose down, center, nose up + uint16_t rudder[3]; ///< Rudder setpoints: nose left, center, nose right + uint16_t gyro[2]; ///< Tail gyro mode/gain setpoints: heading hold, rate mode + uint16_t pitch[5]; ///< Pitch curve setpoints (every 25%) + uint16_t throttle[5]; ///< Throttle curve setpoints (every 25%) } mavlink_radio_calibration_t; @@ -27,25 +27,25 @@ typedef struct __mavlink_radio_calibration_t * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param aileron Aileron setpoints: high, center, low - * @param elevator Elevator setpoints: high, center, low - * @param rudder Rudder setpoints: high, center, low + * @param aileron Aileron setpoints: left, center, right + * @param elevator Elevator setpoints: nose down, center, nose up + * @param rudder Rudder setpoints: nose left, center, nose right * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode * @param pitch Pitch curve setpoints (every 25%) * @param throttle Throttle curve setpoints (every 25%) * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const uint16_t* aileron, const uint16_t* elevator, const uint16_t* rudder, const uint16_t* gyro, const uint16_t* pitch, const uint16_t* throttle) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; - i += put_array_by_index((const int8_t*)aileron, sizeof(float)*3, i, msg->payload); // Aileron setpoints: high, center, low - i += put_array_by_index((const int8_t*)elevator, sizeof(float)*3, i, msg->payload); // Elevator setpoints: high, center, low - i += put_array_by_index((const int8_t*)rudder, sizeof(float)*3, i, msg->payload); // Rudder setpoints: high, center, low - i += put_array_by_index((const int8_t*)gyro, sizeof(float)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode - i += put_array_by_index((const int8_t*)pitch, sizeof(float)*5, i, msg->payload); // Pitch curve setpoints (every 25%) - i += put_array_by_index((const int8_t*)throttle, sizeof(float)*5, i, msg->payload); // Throttle curve setpoints (every 25%) + i += put_array_by_index((const int8_t*)aileron, sizeof(uint16_t)*3, i, msg->payload); // Aileron setpoints: left, center, right + i += put_array_by_index((const int8_t*)elevator, sizeof(uint16_t)*3, i, msg->payload); // Elevator setpoints: nose down, center, nose up + i += put_array_by_index((const int8_t*)rudder, sizeof(uint16_t)*3, i, msg->payload); // Rudder setpoints: nose left, center, nose right + i += put_array_by_index((const int8_t*)gyro, sizeof(uint16_t)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode + i += put_array_by_index((const int8_t*)pitch, sizeof(uint16_t)*5, i, msg->payload); // Pitch curve setpoints (every 25%) + i += put_array_by_index((const int8_t*)throttle, sizeof(uint16_t)*5, i, msg->payload); // Throttle curve setpoints (every 25%) return mavlink_finalize_message(msg, system_id, component_id, i); } @@ -56,25 +56,25 @@ static inline uint16_t mavlink_msg_radio_calibration_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 was sent over * @param msg The MAVLink message to compress the data into - * @param aileron Aileron setpoints: high, center, low - * @param elevator Elevator setpoints: high, center, low - * @param rudder Rudder setpoints: high, center, low + * @param aileron Aileron setpoints: left, center, right + * @param elevator Elevator setpoints: nose down, center, nose up + * @param rudder Rudder setpoints: nose left, center, nose right * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode * @param pitch Pitch curve setpoints (every 25%) * @param throttle Throttle curve setpoints (every 25%) * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const uint16_t* aileron, const uint16_t* elevator, const uint16_t* rudder, const uint16_t* gyro, const uint16_t* pitch, const uint16_t* throttle) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; - i += put_array_by_index((const int8_t*)aileron, sizeof(float)*3, i, msg->payload); // Aileron setpoints: high, center, low - i += put_array_by_index((const int8_t*)elevator, sizeof(float)*3, i, msg->payload); // Elevator setpoints: high, center, low - i += put_array_by_index((const int8_t*)rudder, sizeof(float)*3, i, msg->payload); // Rudder setpoints: high, center, low - i += put_array_by_index((const int8_t*)gyro, sizeof(float)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode - i += put_array_by_index((const int8_t*)pitch, sizeof(float)*5, i, msg->payload); // Pitch curve setpoints (every 25%) - i += put_array_by_index((const int8_t*)throttle, sizeof(float)*5, i, msg->payload); // Throttle curve setpoints (every 25%) + i += put_array_by_index((const int8_t*)aileron, sizeof(uint16_t)*3, i, msg->payload); // Aileron setpoints: left, center, right + i += put_array_by_index((const int8_t*)elevator, sizeof(uint16_t)*3, i, msg->payload); // Elevator setpoints: nose down, center, nose up + i += put_array_by_index((const int8_t*)rudder, sizeof(uint16_t)*3, i, msg->payload); // Rudder setpoints: nose left, center, nose right + i += put_array_by_index((const int8_t*)gyro, sizeof(uint16_t)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode + i += put_array_by_index((const int8_t*)pitch, sizeof(uint16_t)*5, i, msg->payload); // Pitch curve setpoints (every 25%) + i += put_array_by_index((const int8_t*)throttle, sizeof(uint16_t)*5, i, msg->payload); // Throttle curve setpoints (every 25%) return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } @@ -96,16 +96,16 @@ static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, u * @brief Send a radio_calibration message * @param chan MAVLink channel to send the message * - * @param aileron Aileron setpoints: high, center, low - * @param elevator Elevator setpoints: high, center, low - * @param rudder Rudder setpoints: high, center, low + * @param aileron Aileron setpoints: left, center, right + * @param elevator Elevator setpoints: nose down, center, nose up + * @param rudder Rudder setpoints: nose left, center, nose right * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode * @param pitch Pitch curve setpoints (every 25%) * @param throttle Throttle curve setpoints (every 25%) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const uint16_t* aileron, const uint16_t* elevator, const uint16_t* rudder, const uint16_t* gyro, const uint16_t* pitch, const uint16_t* throttle) { mavlink_message_t msg; mavlink_msg_radio_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, aileron, elevator, rudder, gyro, pitch, throttle); @@ -118,37 +118,37 @@ static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, co /** * @brief Get field aileron from radio_calibration message * - * @return Aileron setpoints: high, center, low + * @return Aileron setpoints: left, center, right */ -static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, float* r_data) +static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, uint16_t* r_data) { - memcpy(r_data, msg->payload, sizeof(float)*3); - return sizeof(float)*3; + memcpy(r_data, msg->payload, sizeof(uint16_t)*3); + return sizeof(uint16_t)*3; } /** * @brief Get field elevator from radio_calibration message * - * @return Elevator setpoints: high, center, low + * @return Elevator setpoints: nose down, center, nose up */ -static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, float* r_data) +static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, uint16_t* r_data) { - memcpy(r_data, msg->payload+sizeof(float)*3, sizeof(float)*3); - return sizeof(float)*3; + memcpy(r_data, msg->payload+sizeof(uint16_t)*3, sizeof(uint16_t)*3); + return sizeof(uint16_t)*3; } /** * @brief Get field rudder from radio_calibration message * - * @return Rudder setpoints: high, center, low + * @return Rudder setpoints: nose left, center, nose right */ -static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, float* r_data) +static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, uint16_t* r_data) { - memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3, sizeof(float)*3); - return sizeof(float)*3; + memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3, sizeof(uint16_t)*3); + return sizeof(uint16_t)*3; } /** @@ -156,11 +156,11 @@ static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_me * * @return Tail gyro mode/gain setpoints: heading hold, rate mode */ -static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, float* r_data) +static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, uint16_t* r_data) { - memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3, sizeof(float)*2); - return sizeof(float)*2; + memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*3, sizeof(uint16_t)*2); + return sizeof(uint16_t)*2; } /** @@ -168,11 +168,11 @@ static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_mess * * @return Pitch curve setpoints (every 25%) */ -static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, float* r_data) +static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, uint16_t* r_data) { - memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3+sizeof(float)*2, sizeof(float)*5); - return sizeof(float)*5; + memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*2, sizeof(uint16_t)*5); + return sizeof(uint16_t)*5; } /** @@ -180,11 +180,11 @@ static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_mes * * @return Throttle curve setpoints (every 25%) */ -static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, float* r_data) +static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, uint16_t* r_data) { - memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3+sizeof(float)*2+sizeof(float)*5, sizeof(float)*5); - return sizeof(float)*5; + memcpy(r_data, msg->payload+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*3+sizeof(uint16_t)*2+sizeof(uint16_t)*5, sizeof(uint16_t)*5); + return sizeof(uint16_t)*5; } /** diff --git a/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h b/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h new file mode 100644 index 0000000000..50e8f7d02c --- /dev/null +++ b/libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h @@ -0,0 +1,135 @@ +// MESSAGE UALBERTA_SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_UALBERTA_SYS_STATUS 222 + +typedef struct __mavlink_ualberta_sys_status_t +{ + uint8_t mode; ///< System mode, see UALBERTA_AUTOPILOT_MODE ENUM + uint8_t nav_mode; ///< Navigation mode, see UALBERTA_NAV_MODE ENUM + uint8_t pilot; ///< Pilot mode, see UALBERTA_PILOT_MODE + +} mavlink_ualberta_sys_status_t; + + + +/** + * @brief Pack a ualberta_sys_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 mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM + * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM + * @param pilot Pilot mode, see UALBERTA_PILOT_MODE + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ualberta_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t pilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS; + + i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see UALBERTA_AUTOPILOT_MODE ENUM + i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see UALBERTA_NAV_MODE ENUM + i += put_uint8_t_by_index(pilot, i, msg->payload); // Pilot mode, see UALBERTA_PILOT_MODE + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a ualberta_sys_status message + * @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 was sent over + * @param msg The MAVLink message to compress the data into + * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM + * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM + * @param pilot Pilot mode, see UALBERTA_PILOT_MODE + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ualberta_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t pilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS; + + i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see UALBERTA_AUTOPILOT_MODE ENUM + i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see UALBERTA_NAV_MODE ENUM + i += put_uint8_t_by_index(pilot, i, msg->payload); // Pilot mode, see UALBERTA_PILOT_MODE + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a ualberta_sys_status struct into a 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 ualberta_sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ualberta_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ualberta_sys_status_t* ualberta_sys_status) +{ + return mavlink_msg_ualberta_sys_status_pack(system_id, component_id, msg, ualberta_sys_status->mode, ualberta_sys_status->nav_mode, ualberta_sys_status->pilot); +} + +/** + * @brief Send a ualberta_sys_status message + * @param chan MAVLink channel to send the message + * + * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM + * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM + * @param pilot Pilot mode, see UALBERTA_PILOT_MODE + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ualberta_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t pilot) +{ + mavlink_message_t msg; + mavlink_msg_ualberta_sys_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, nav_mode, pilot); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE UALBERTA_SYS_STATUS UNPACKING + +/** + * @brief Get field mode from ualberta_sys_status message + * + * @return System mode, see UALBERTA_AUTOPILOT_MODE ENUM + */ +static inline uint8_t mavlink_msg_ualberta_sys_status_get_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field nav_mode from ualberta_sys_status message + * + * @return Navigation mode, see UALBERTA_NAV_MODE ENUM + */ +static inline uint8_t mavlink_msg_ualberta_sys_status_get_nav_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field pilot from ualberta_sys_status message + * + * @return Pilot mode, see UALBERTA_PILOT_MODE + */ +static inline uint8_t mavlink_msg_ualberta_sys_status_get_pilot(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a ualberta_sys_status message into a struct + * + * @param msg The message to decode + * @param ualberta_sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_ualberta_sys_status_decode(const mavlink_message_t* msg, mavlink_ualberta_sys_status_t* ualberta_sys_status) +{ + ualberta_sys_status->mode = mavlink_msg_ualberta_sys_status_get_mode(msg); + ualberta_sys_status->nav_mode = mavlink_msg_ualberta_sys_status_get_nav_mode(msg); + ualberta_sys_status->pilot = mavlink_msg_ualberta_sys_status_get_pilot(msg); +} diff --git a/libraries/GCS_MAVLink/include/ualberta/ualberta.h b/libraries/GCS_MAVLink/include/ualberta/ualberta.h index 1583d64fb5..be77cc2e5d 100644 --- a/libraries/GCS_MAVLink/include/ualberta/ualberta.h +++ b/libraries/GCS_MAVLink/include/ualberta/ualberta.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. - * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Saturday, April 16 2011, 04:02 UTC + * @see http://qgroundcontrol.org/mavlink/ + * Generated on Friday, August 5 2011, 07:37 UTC */ #ifndef UALBERTA_H #define UALBERTA_H @@ -30,18 +30,48 @@ extern "C" { // ENUM DEFINITIONS +/** @brief Available autopilot modes for ualberta uav */ +enum UALBERTA_AUTOPILOT_MODE +{ + MODE_MANUAL_DIRECT=0, /* */ + MODE_MANUAL_SCALED=1, /* */ + MODE_AUTO_PID_ATT=2, /* */ + MODE_AUTO_PID_VEL=3, /* */ + MODE_AUTO_PID_POS=4, /* */ + UALBERTA_AUTOPILOT_MODE_ENUM_END +}; + +/** @brief Navigation filter mode */ +enum UALBERTA_NAV_MODE +{ + NAV_AHRS_INIT=0, + NAV_AHRS=1, /* */ + NAV_INS_GPS_INIT=2, /* */ + NAV_INS_GPS=3, /* */ + UALBERTA_NAV_MODE_ENUM_END +}; + +/** @brief Mode currently commanded by pilot */ +enum UALBERTA_PILOT_MODE +{ + PILOT_MANUAL=0, /* */ + PILOT_AUTO=1, /* */ + PILOT_ROTO=2, /* */ + UALBERTA_PILOT_MODE_ENUM_END +}; + // MESSAGE DEFINITIONS #include "./mavlink_msg_nav_filter_bias.h" -#include "./mavlink_msg_request_rc_channels.h" #include "./mavlink_msg_radio_calibration.h" +#include "./mavlink_msg_ualberta_sys_status.h" // MESSAGE LENGTHS #undef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 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, 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, 32, 1, 84, 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, 30, 14, 14, 51 } +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 14, 14, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 56, 0, 21, 18, 0, 0, 18, 20, 20, 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, 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, 32, 42, 3, 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, 30, 14, 14, 51 } #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 39d96eab51..72bf88a7cf 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -1,6 +1,6 @@ - common.xml - - + common.xml + + diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index c2d977841d..4a468ec26c 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -1,908 +1,920 @@ - + -2 - - - - 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. - - Navigate to waypoint. - Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) - Acceptance radius in meters (if the sphere with this radius is hit, the waypoint 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 waypoint (rotary wing) - Latitude - Longitude - Altitude - - - Loiter around this waypoint an unlimited amount of time - Empty - Empty - Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise - Desired yaw angle. - Latitude - Longitude - Altitude - - - Loiter around this waypoint for X turns - Turns - Empty - Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise - Desired yaw angle. - Latitude - Longitude - Altitude - - - Loiter around this waypoint for X seconds - Seconds (decimal) - Empty - Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise - Desired yaw angle. - Latitude - Longitude - Altitude - - - Return to launch location - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Land at location - Empty - Empty - Empty - Desired yaw angle. - Latitude - Longitude - Altitude - - - 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 - - - - 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 - - - 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 - - - Delay mission state machine. - Delay in seconds (decimal) - Empty - Empty - Empty - Empty - Empty - Empty - - - Ascend/descend at rate. Delay mission state machine until desired altitude reached. - Descent / Ascend rate (m/s) - Empty - Empty - Empty - Empty - Empty - Finish Altitude - - - Delay mission state machine until within desired distance of next NAV point. - Distance (meters) - Empty - Empty - Empty - Empty - Empty - Empty - - - 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 - - - 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 - - - Set system mode. - Mode, as defined by ENUM MAV_MODE - Empty - Empty - Empty - Empty - Empty - Empty - - - 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 - - - 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) - Empty - Empty - Empty - Empty - - - 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 - - - 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 - - - Set a relay to a condition. - Relay number - Setting (1=on, 0=off, others possible depending on system hardware) - Empty - Empty - Empty - Empty - Empty - - - 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 - - - Set a servo to a desired PWM value. - Servo number - PWM (microseconds, 1000 to 2000 typical) - Empty - Empty - Empty - Empty - Empty - - - 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 - - - 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 - - - - 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 - devices such as cameras. - Region of interest mode. (see MAV_ROI enum) - Waypoint index/ target ID. (see MAV_ROI enum) - ROI index (allows a vehicle to manage multiple cameras etc.) - Empty - x the location of the fixed ROI (see MAV_FRAME) - y - z - - - - 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 - - - Trigger calibration. This command will be only accepted if in pre-flight mode. - Gyro calibration: 0: no, 1: yes - Magnetometer calibration: 0: no, 1: yes - Ground pressure: 0: no, 1: yes - Radio calibration: 0: no, 1: yes - Empty - Empty - Empty - - - 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 - Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM - Reserved - Reserved - Empty - Empty - Empty - - - - Data stream IDs. 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. - - Enable all data streams - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. - Dependent on the autopilot - Dependent on the autopilot - Dependent on the autopilot - - - - The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_DO_SET_ROI). - - No region of interest. - Point toward next waypoint. - Point toward given waypoint. - Point toward fixed location. - Point toward target of given id. - - - - - - - The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). - Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM - MAVLink version - - - - The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. - The onboard software version - - - - The system time is the time of the master clock, typically the computer clock of the main onboard computer. - Timestamp of the master clock in microseconds since UNIX epoch. - - - - A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. - PING sequence - 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 - 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 - Unix timestamp in microseconds - - - - UTC date and time from GPS module - GPS UTC date ddmmyy - GPS UTC time hhmmss - - - - Request to control this MAV - System the GCS requests control for - 0: request control of this MAV, 1: Release control of this MAV - 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. - 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 "!?,.-" - - - - Accept / deny control of this MAV - ID of the GCS this message - 0: request control of this MAV, 1: Release control of this MAV - 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - - - - Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. - key - - - - This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h - The action id - 0: Action DENIED, 1: Action executed - - - - An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h - The system executing the action - The component executing the action - The action id - - - - Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. - The system setting the mode - The new mode - - - - Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components. - The system setting the mode - The new navigation mode - - - - Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. - System ID - Component ID - Onboard parameter id - Parameter index. Send -1 to use the param ID field as identifier - - - - Request all parameters of this component. After his request, all parameters are emitted. - System ID - Component ID - - - - Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. - Onboard parameter id - Onboard parameter value - Total number of onboard parameters - Index of this onboard parameter - - - - Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. - System ID - Component ID - Onboard parameter id - Onboard parameter value - - - - The global position, as returned by the Global Positioning System (GPS). This is -NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - 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. - Latitude in 1E7 degrees - Longitude in 1E7 degrees - Altitude in 1E3 meters (millimeters) - GPS HDOP - GPS VDOP - GPS ground speed (m/s) - Compass heading in degrees, 0..360 degrees - - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - - The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. - Number of satellites visible - Global satellite ID - 0: Satellite not used, 1: used for localization - Elevation (0: right on top of receiver, 90: on the horizon) of satellite - Direction of satellite, 0: 0 deg, 255: 360 deg. - Signal to noise ratio of satellite - - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - X acceleration (raw) - Y acceleration (raw) - Z acceleration (raw) - Angular speed around X axis (raw) - Angular speed around Y axis (raw) - Angular speed around Z axis (raw) - X Magnetic field (raw) - Y Magnetic field (raw) - Z Magnetic field (raw) - - - - The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Absolute pressure (raw) - Differential pressure 1 (raw) - Differential pressure 2 (raw) - Raw Temperature measurement (raw) - - - - The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Roll angle (rad) - Pitch angle (rad) - Yaw angle (rad) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame) - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - X Position - Y Position - Z Position - X Speed - Y Speed - Z Speed - - - - - The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame) - Timestamp (microseconds since unix epoch) - Latitude, in degrees - Longitude, in degrees - Absolute altitude, in meters - X Speed (in Latitude direction, positive: going north) - Y Speed (in Longitude direction, positive: going east) - Z Speed (in Altitude direction, positive: going up) - - - - The global position, as returned by the Global Positioning System (GPS). This is -NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - 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. - Latitude in degrees - Longitude in degrees - Altitude in meters - GPS HDOP - GPS VDOP - GPS ground speed - Compass heading in degrees, 0..360 degrees - - - - The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. - System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h - Navigation mode, see MAV_NAV_MODE ENUM - System status flag, see MAV_STATUS ENUM - Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - Battery voltage, in millivolts (1 = 1 millivolt) - Remaining battery energy: (0%: 0, 100%: 1000) - Dropped packets (packets that were corrupted on reception on the MAV) - - - - The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - RC channel 1 value, in microseconds - RC channel 2 value, in microseconds - RC channel 3 value, in microseconds - RC channel 4 value, in microseconds - RC channel 5 value, in microseconds - RC channel 6 value, in microseconds - RC channel 7 value, in microseconds - RC channel 8 value, in microseconds - Receive signal strength indicator, 0: 0%, 255: 100% - - - - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - Receive signal strength indicator, 0: 0%, 255: 100% - - - - The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. - Servo output 1 value, in microseconds - Servo output 2 value, in microseconds - Servo output 3 value, in microseconds - Servo output 4 value, in microseconds - Servo output 5 value, in microseconds - Servo output 6 value, in microseconds - Servo output 7 value, in microseconds - Servo output 8 value, in microseconds - - - - Message encoding a waypoint. This message is emitted to announce - the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed - System ID - Component ID - Sequence - The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h - The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters - PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH - PARAM5 / local: x position, global: latitude - PARAM6 / y position: global: longitude - PARAM7 / z position: global: altitude - - - - Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message. - System ID - Component ID - Sequence - - - - Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between). - System ID - Component ID - Sequence - - - - Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint. - Sequence - - - - Request the overall list of waypoints from the system/component. - System ID - Component ID - - - - This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints. - System ID - Component ID - Number of Waypoints in the Sequence - - - - Delete all waypoints at once. - System ID - Component ID - - - - A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. - Sequence - - - - Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). - System ID - Component ID - 0: OK, 1: Error - - - - As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. - System ID - Component ID - global position * 1E7 - global position * 1E7 - global position * 1000 - - - - Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position - Latitude (WGS84), expressed as * 1E7 - Longitude (WGS84), expressed as * 1E7 - Altitude(WGS84), expressed as * 1000 - - - - Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. - System ID - Component ID - x position - y position - z position - Desired yaw angle - - - - Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. - x position - y position - z position - Desired yaw angle - - - - Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix - Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix - GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix - Attitude estimation health: 0: poor, 255: excellent - 0: Attitude control disabled, 1: enabled - 0: X, Y position control disabled, 1: enabled - 0: Z position control disabled, 1: enabled - 0: Yaw angle control disabled, 1: enabled - - - - Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. - System ID - Component ID - 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. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - - Read out the safety zone the MAV currently assumes. - 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. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - - The output of the attitude controller. This output is the control response the controller currently generates and the attitude the MAV would take if it is under control of the attitude controller. The primary use of this message is to check the response and signs of the controller before the actual flight. - 1: enabled, 0: disabled - Attitude roll: -128: -100%, 127: +100% - Attitude pitch: -128: -100%, 127: +100% - Attitude yaw: -128: -100%, 127: +100% - Attitude thrust: -128: -100%, 127: +100% - - - - The output of the position controller. The primary use of this message is to check the response and signs of the controller before the actual flight. - 1: enabled, 0: disabled - Position x: -128: -100%, 127: +100% - Position y: -128: -100%, 127: +100% - Position z: -128: -100%, 127: +100% - Position yaw: -128: -100%, 127: +100% - - - - Outputs of the APM navigation controller. The primary use of this message is to check the response and signs -of the controller before actual flight and to assist with tuning controller parameters - Current desired roll in degrees - Current desired pitch in degrees - Current desired heading in degrees - Bearing to current waypoint/target in degrees - Distance to active waypoint in meters - Current altitude error in meters - Current airspeed error in meters/second - Current crosstrack error on x-y plane in meters - - - - The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint. - x position - y position - z position - yaw orientation in radians, 0 = NORTH - - - - Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. - x position error - y position error - z position error - roll error (radians) - pitch error (radians) - yaw error (radians) - x velocity - y velocity - z velocity - - - - The system setting the altitude - The new altitude in meters - - - - The target requested to send the message stream. - The target requested to send the message stream. - The ID of the requested message type - The requested interval between two messages of this type - 1 to start sending, 0 to stop sending. - - - - The system to be controlled - roll - pitch - yaw - thrust - roll control enabled auto:0, manual:1 - pitch auto:0, manual:1 - yaw auto:0, manual:1 - thrust auto:0, manual:1 - - - - The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - System ID - Component ID - RC channel 1 value, in microseconds - RC channel 2 value, in microseconds - RC channel 3 value, in microseconds - RC channel 4 value, in microseconds - RC channel 5 value, in microseconds - RC channel 6 value, in microseconds - RC channel 7 value, in microseconds - RC channel 8 value, in microseconds - - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up) - Latitude, expressed as * 1E7 - Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as m/s * 100 - Ground Y Speed (Longitude), expressed as m/s * 100 - Ground Z Speed (Altitude), expressed as m/s * 100 - - - - Metrics typically displayed on a HUD for fixed wing aircraft - Current airspeed in m/s - Current ground speed in m/s - Current heading in degrees, in compass units (0..360, 0=north) - Current throttle setting in integer percent, 0 to 100 - Current altitude (MSL), in meters - Current climb rate in meters/second - - - - Send a command with up to four parameters to the MAV - System which should execute the command - Component which should execute the command, 0 for all components - Command ID, as defined by MAV_CMD enum. - 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - Parameter 1, as defined by MAV_CMD enum. - Parameter 2, as defined by MAV_CMD enum. - Parameter 3, as defined by MAV_CMD enum. - Parameter 4, as defined by MAV_CMD enum. - - - - Report status of a command. Includes feedback wether the command was executed - Current airspeed in m/s - 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION - - - - - - - - - Name - Timestamp - x - y - z - - - - Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Name of the debug variable - Floating point value - - - - Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Name of the debug variable - Signed integer value - - - - Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). - Severity of status, 0 = info message, 255 = critical fault - Status text message, without null termination character - - - - Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. - index of debug variable - DEBUG value - - - + 2 + + + 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. + + + Navigate to waypoint. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the waypoint 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 waypoint (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this waypoint an unlimited amount of time + Empty + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X turns + Turns + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X seconds + Seconds (decimal) + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Empty + Empty + Empty + Desired yaw angle. + Latitude + Longitude + Altitude + + + 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 + + + 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) + 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 + + + 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 + + + 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 + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + 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 + + + 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 + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Empty + Empty + Empty + Empty + Empty + Empty + + + 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 + + + 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) + Empty + Empty + Empty + Empty + + + 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 + + + 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 + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + 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 + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + 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 + + + Control onboard camera capturing. + 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 + + + + 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 + devices such as cameras. + + Region of interest mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple cameras etc.) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + + 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 + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Empty + Empty + Empty + + + 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 + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Reserved + Reserved + Empty + Empty + Empty + + + + Data stream IDs. 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. + + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + 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). + + + No region of interest. + + + Point toward next waypoint. + + + Point toward given waypoint. + + + Point toward fixed location. + + + Point toward of given id. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. + The onboard software version + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + PING sequence + 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 + 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 + Unix timestamp in microseconds + + + UTC date and time from GPS module + GPS UTC date ddmmyy + GPS UTC time hhmmss + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 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. + 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 "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The action id + 0: Action DENIED, 1: Action executed + + + An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The system executing the action + The component executing the action + The action id + + + Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new mode + + + Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components. + The system setting the mode + The new navigation mode + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id + Parameter index. Send -1 to use the param ID field as identifier + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id + Onboard parameter value + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id + Onboard parameter value + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 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. + Latitude in 1E7 degrees + Longitude in 1E7 degrees + Altitude in 1E3 meters (millimeters) + GPS HDOP + GPS VDOP + GPS ground speed (m/s) + Compass heading in degrees, 0..360 degrees + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw) + Differential pressure 2 (raw) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since unix epoch) + Latitude, in degrees + Longitude, in degrees + Absolute altitude, in meters + X Speed (in Latitude direction, positive: going north) + Y Speed (in Longitude direction, positive: going east) + Z Speed (in Altitude direction, positive: going up) + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 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. + Latitude in degrees + Longitude in degrees + Altitude in meters + GPS HDOP + GPS VDOP + GPS ground speed + Compass heading in degrees, 0..360 degrees + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + Navigation mode, see MAV_NAV_MODE ENUM + System status flag, see MAV_STATUS ENUM + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Remaining battery energy: (0%: 0, 100%: 1000) + Dropped packets (packets that were corrupted on reception on the MAV) + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + Receive signal strength indicator, 0: 0%, 255: 100% + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed + + System ID + Component ID + Sequence + The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude + + + Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message. + System ID + Component ID + Sequence + + + Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint. + Sequence + + + Request the overall list of waypoints from the system/component. + System ID + Component ID + + + This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints. + System ID + Component ID + Number of Waypoints in the Sequence + + + Delete all waypoints at once. + System ID + Component ID + + + A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. + Sequence + + + Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + 0: OK, 1: Error + + + As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Component ID + global position * 1E7 + global position * 1E7 + global position * 1000 + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), expressed as * 1E7 + Longitude (WGS84), expressed as * 1E7 + Altitude(WGS84), expressed as * 1000 + + + Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. + System ID + Component ID + x position + y position + z position + Desired yaw angle + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + x position + y position + z position + Desired yaw angle + + + Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + Attitude estimation health: 0: poor, 255: excellent + 0: Attitude control disabled, 1: enabled + 0: X, Y position control disabled, 1: enabled + 0: Z position control disabled, 1: enabled + 0: Yaw angle control disabled, 1: enabled + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + 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. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + 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. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + + + The output of the attitude controller. This output is the control response the controller currently generates and the attitude the MAV would take if it is under control of the attitude controller. The primary use of this message is to check the response and signs of the controller before the actual flight. + 1: enabled, 0: disabled + Attitude roll: -128: -100%, 127: +100% + Attitude pitch: -128: -100%, 127: +100% + Attitude yaw: -128: -100%, 127: +100% + Attitude thrust: -128: -100%, 127: +100% + + + The output of the position controller. The primary use of this message is to check the response and signs of the controller before the actual flight. + 1: enabled, 0: disabled + Position x: -128: -100%, 127: +100% + Position y: -128: -100%, 127: +100% + Position z: -128: -100%, 127: +100% + Position yaw: -128: -100%, 127: +100% + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs + of the controller before actual flight and to assist with tuning controller parameters + + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current waypoint/target in degrees + Distance to active waypoint in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint. + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. + x position error + y position error + z position error + roll error (radians) + pitch error (radians) + yaw error (radians) + x velocity + y velocity + z velocity + + + The system setting the altitude + The new altitude in meters + + + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested message type + The requested interval between two messages of this type + 1 to start sending, 0 to stop sending. + + + + This packet is useful for high throughput + applications such as hardware in the loop. + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Send a command with up to four parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed + Current airspeed in m/s + 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status, 0 = info message, 255 = critical fault + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + index of debug variable + DEBUG value + + diff --git a/libraries/GCS_MAVLink/message_definitions/minimal.xml b/libraries/GCS_MAVLink/message_definitions/minimal.xml new file mode 100644 index 0000000000..5b41a49090 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/minimal.xml @@ -0,0 +1,13 @@ + + + 2 + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + diff --git a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml index 55e53205aa..51b7db1a3e 100644 --- a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml +++ b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml @@ -1,253 +1,264 @@ -common.xml - - - - Slugs parameter interface subsets - - With comment: PID Pitch parameter - - - - - Content Types for data transmission handshake - - - - - - - - - The system to be controlled - roll - pitch - yaw - thrust - roll control enabled auto:0, manual:1 - pitch auto:0, manual:1 - yaw auto:0, manual:1 - thrust auto:0, manual:1 - - - - Camera id - Camera mode: 0 = auto, 1 = manual - Trigger pin, 0-3 for PtGrey FireFly - Shutter interval, in microseconds - Exposure time, in microseconds - Camera gain - - - - Timestamp - IMU seq - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - Local frame Z coordinate (height over ground) - GPS X coordinate - GPS Y coordinate - Global frame altitude - - - - 0 to disable, 1 to enable - - - - Camera id - Camera # (starts with 0) - Timestamp - Until which timestamp this buffer will stay valid - The image sequence number - Position of the image in the buffer, starts with 0 - Image width - Image height - Image depth - Image channels - Shared memory area key - Exposure time, in microseconds - Camera gain - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - Local frame Z coordinate (height over ground) - GPS X coordinate - GPS Y coordinate - Global frame altitude - - - - Timestamp (milliseconds) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - - Timestamp (milliseconds) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - - Message sent to the MAV to set a new position as reference for the controller - System ID - Component ID - ID of waypoint, 0 for plain position - x position - y position - z position - yaw orientation in radians, 0 = NORTH - - - - Message sent to the MAV to set a new offset from the currently controlled position - System ID - Component ID - x position offset - y position offset - z position offset - yaw orientation offset in radians, 0 = NORTH - - - - - ID of waypoint, 0 for plain position - x position - y position - z position - yaw orientation in radians, 0 = NORTH - - - - ID - x position - y position - z position - roll orientation - pitch orientation - yaw orientation - - - - ADC1 (J405 ADC3, LPC2148 AD0.6) - ADC2 (J405 ADC5, LPC2148 AD0.2) - ADC3 (J405 ADC6, LPC2148 AD0.1) - ADC4 (J405 ADC7, LPC2148 AD1.3) - Battery voltage - Temperature (degrees celcius) - Barometric pressure (hecto Pascal) - - - - Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - Number of I2C errors since startup -Number of I2C errors since startup - Number of I2C errors since startup -Number of I2C errors since startup - Number of I2C errors since startup - - - - Watchdog ID - Number of processes - - - - Watchdog ID - Process ID - Process name - Process arguments - Timeout (seconds) - - - - Watchdog ID - Process ID - Is running / finished / suspended / crashed - Is muted - PID - Number of crashes - - - - Target system ID - Watchdog ID - Process ID - Command ID - - - - 0: Pattern, 1: Letter - Confidence of detection - Pattern file name - Accepted as true detection, 0 no, 1 yes - - - - Notifies the operator about a point of interest (POI). This can be anything detected by the - system. This generic message is intented to help interfacing to generic visualizations and to display - the POI on a map. - 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - 0: global, 1:local - 0: no timeout, >1: timeout in seconds - X Position - Y Position - Z Position - POI name - - - - Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the - system. This generic message is intented to help interfacing to generic visualizations and to display - the POI on a map. - 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - 0: global, 1:local - 0: no timeout, >1: timeout in seconds - X1 Position - Y1 Position - Z1 Position - X2 Position - Y2 Position - Z2 Position - POI connection name - - - - type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - total data size in bytes (set on ACK only) - number of packets beeing sent (set on ACK only) - payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - JPEG quality out of [1,100] - - - - sequence number (starting with 0 on every transmission) - image data bytes - - - - x position in m - y position in m - z position in m - Orientation assignment 0: false, 1:true - Size in pixels - Orientation - Descriptor - Harris operator response at this location - - - + common.xml + + + + Content Types for data transmission handshake + + + + + + + + + + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + + Camera id + Camera mode: 0 = auto, 1 = manual + Trigger pin, 0-3 for PtGrey FireFly + Shutter interval, in microseconds + Exposure time, in microseconds + Camera gain + + + + Timestamp + IMU seq + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + Ground truth X + Ground truth Y + Ground truth Z + + + + 0 to disable, 1 to enable + + + + Camera id + Camera # (starts with 0) + Timestamp + Until which timestamp this buffer will stay valid + The image sequence number + Position of the image in the buffer, starts with 0 + Image width + Image height + Image depth + Image channels + Shared memory area key + Exposure time, in microseconds + Camera gain + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + Ground truth X + Ground truth Y + Ground truth Z + + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Timestamp (milliseconds) + Global X speed + Global Y speed + Global Z speed + + + + Message sent to the MAV to set a new position as reference for the controller + System ID + Component ID + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + Message sent to the MAV to set a new offset from the currently controlled position + System ID + Component ID + x position offset + y position offset + z position offset + yaw orientation offset in radians, 0 = NORTH + + + + + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + ID + x position + y position + z position + roll orientation + pitch orientation + yaw orientation + + + + ADC1 (J405 ADC3, LPC2148 AD0.6) + ADC2 (J405 ADC5, LPC2148 AD0.2) + ADC3 (J405 ADC6, LPC2148 AD0.1) + ADC4 (J405 ADC7, LPC2148 AD1.3) + Battery voltage + Temperature (degrees celcius) + Barometric pressure (hecto Pascal) + + + + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Number of I2C errors since startup + Number of I2C errors since startup + Number of I2C errors since startup + Number of I2C errors since startup + Number of I2C errors since startup + + + + Watchdog ID + Number of processes + + + + Watchdog ID + Process ID + Process name + Process arguments + Timeout (seconds) + + + + Watchdog ID + Process ID + Is running / finished / suspended / crashed + Is muted + PID + Number of crashes + + + + Target system ID + Watchdog ID + Process ID + Command ID + + + + 0: Pattern, 1: Letter + Confidence of detection + Pattern file name + Accepted as true detection, 0 no, 1 yes + + + + Notifies the operator about a point of interest (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X Position + Y Position + Z Position + POI name + + + + Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X1 Position + Y1 Position + Z1 Position + X2 Position + Y2 Position + Z2 Position + POI connection name + + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + + sequence number (starting with 0 on every transmission) + image data bytes + + + + x position in m + y position in m + z position in m + Orientation assignment 0: false, 1:true + Size in pixels + Orientation + Descriptor + Harris operator response at this location + + + diff --git a/libraries/GCS_MAVLink/message_definitions/slugs.xml b/libraries/GCS_MAVLink/message_definitions/slugs.xml index 6de0697fef..f8644c5c4b 100644 --- a/libraries/GCS_MAVLink/message_definitions/slugs.xml +++ b/libraries/GCS_MAVLink/message_definitions/slugs.xml @@ -1,8 +1,8 @@ -common.xml - - - - - - - Sensor and DSC control loads. - Sensor DSC Load - Control DSC Load - Battery Voltage in millivolts - - - - Air data for altitude and airspeed computation. - Dynamic pressure (Pa) - Static pressure (Pa) - Board temperature - - - - Accelerometer and gyro biases. - Accelerometer X bias (m/s) - Accelerometer Y bias (m/s) - Accelerometer Z bias (m/s) - Gyro X bias (rad/s) - Gyro Y bias (rad/s) - Gyro Z bias (rad/s) - - - - Configurable diagnostic messages. - Diagnostic float 1 - Diagnostic float 2 - Diagnostic float 3 - Diagnostic short 1 - Diagnostic short 2 - Diagnostic short 3 - - - - Data used in the navigation algorithm. - Measured Airspeed prior to the Nav Filter - Commanded Roll - Commanded Pitch - Commanded Turn rate - Y component of the body acceleration - Total Distance to Run on this leg of Navigation - Remaining distance to Run on this leg of Navigation - Origin WP - Destination WP - - - - Configurable data log probes to be used inside Simulink - Log value 1 - Log value 2 - Log value 3 - Log value 4 - Log value 5 - Log value 6 - - - - Pilot console PWM messges. - Year reported by Gps - Month reported by Gps - Day reported by Gps - Hour reported by Gps - Min reported by Gps - Sec reported by Gps - Visible sattelites reported by Gps - - - Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. - The system setting the commands - Commanded Airspeed - Log value 2 - Log value 3 - - - -This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: - Position Bit Code - ================================= - 15-8 Reserved - 7 dt_pass 128 - 6 dla_pass 64 - 5 dra_pass 32 - 4 dr_pass 16 - 3 dle_pass 8 - 2 dre_pass 4 - 1 dlf_pass 2 - 0 drf_pass 1 - Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. - The system setting the commands - Bitfield containing the PT configuration - - - - - Action messages focused on the SLUGS AP. - The system reporting the action - Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names - Value associated with the action - - - - \ No newline at end of file + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Air data for altitude and airspeed computation. + Dynamic pressure (Pa) + Static pressure (Pa) + Board temperature + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the Nav Filter + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Visible sattelites reported by Gps + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + The system setting the commands + Commanded Airspeed + Log value 2 + Log value 3 + + + + + This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + The system setting the commands + Bitfield containing the PT configuration + + + + + + Action messages focused on the SLUGS AP. + The system reporting the action + Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + Value associated with the action + + + + diff --git a/libraries/GCS_MAVLink/message_definitions/ualberta.xml b/libraries/GCS_MAVLink/message_definitions/ualberta.xml index ef28d6e914..5e53e141e9 100644 --- a/libraries/GCS_MAVLink/message_definitions/ualberta.xml +++ b/libraries/GCS_MAVLink/message_definitions/ualberta.xml @@ -1,29 +1,54 @@ - + - common.xml - - - Accelerometer and Gyro biases from the navigation filter - Timestamp (microseconds) - b_f[0] - b_f[1] - b_f[2] - b_f[0] - b_f[1] - b_f[2] - - - Request raw and normalized rc data from the UAV - True: start sending data; False: stop sending data - - - Complete set of calibration parameters for the radio - Aileron setpoints: high, center, low - Elevator setpoints: high, center, low - Rudder setpoints: high, center, low - Tail gyro mode/gain setpoints: heading hold, rate mode - Pitch curve setpoints (every 25%) - Throttle curve setpoints (every 25%) - - + common.xml + + + Available autopilot modes for ualberta uav + Raw input pulse widts sent to output + Inputs are normalized using calibration, the converted back to raw pulse widths for output + dfsdfs + dfsfds + dfsdfsdfs + + + Navigation filter mode + + AHRS mode + INS/GPS initialization mode + INS/GPS mode + + + Mode currently commanded by pilot + sdf + dfs + Rotomotion mode + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + diff --git a/libraries/GCS_MAVLink/missionlib/testing/.gitignore b/libraries/GCS_MAVLink/missionlib/testing/.gitignore new file mode 100644 index 0000000000..0776965a63 --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/.gitignore @@ -0,0 +1,3 @@ +*.o +udptest +build diff --git a/libraries/GCS_MAVLink/missionlib/testing/Makefile b/libraries/GCS_MAVLink/missionlib/testing/Makefile new file mode 100644 index 0000000000..134aa47fc4 --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/Makefile @@ -0,0 +1,12 @@ +VERSION = 1.00 +CC = gcc +CFLAGS = -I ../../include/common -Wall -Werror -DVERSION=\"$(MAVLINK_VERSION)\" -std=c99 +LDFLAGS = "" + +OBJ = udp.o + +udptest: $(OBJ) + $(CC) $(CFLAGS) -o udptest $(OBJ) $(LDFLAGS) + +%.o: %.c + $(CC) $(CFLAGS) -c $< \ No newline at end of file diff --git a/libraries/GCS_MAVLink/missionlib/testing/main.c b/libraries/GCS_MAVLink/missionlib/testing/main.c new file mode 100644 index 0000000000..9e2dc55a26 --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/main.c @@ -0,0 +1,255 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + and Bryan Godbolt godbolt ( a t ) ualberta.ca + + adapted from example written by Bryan Godbolt godbolt ( a t ) ualberta.ca + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + + ****************************************************************************/ +/* + This program sends some data to qgroundcontrol using the mavlink protocol. The sent packets + cause qgroundcontrol to respond with heartbeats. Any settings or custom commands sent from + qgroundcontrol are printed by this program along with the heartbeats. + + + I compiled this program sucessfully on Ubuntu 10.04 with the following command + + gcc -I ../../pixhawk/mavlink/include -o udp-server udp.c + + the rt library is needed for the clock_gettime on linux + */ +/* These headers are for QNX, but should all be standard on unix/linux */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if (defined __QNX__) | (defined __QNXNTO__) +/* QNX specific headers */ +#include +#else +/* Linux / MacOS POSIX timer headers */ +#include +#include +#include +#endif + +#include + +#include <../mavlink_types.h> + +mavlink_system_t mavlink_system; + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ +#include + + +/* Provide the interface functions for the waypoint manager */ + +/* + * @brief Sends a MAVLink message over UDP + */ +void mavlink_wpm_send_message(mavlink_message_t* msg) +{ + uint16_t len = mavlink_msg_to_send_buffer(buf, msg); + uint16_t bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in)); + + printf("SENT %d bytes", bytes_sent); +} + + +#include + + +#define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why) + +char help[] = "--help"; + + +char target_ip[100]; + +float position[6] = {}; +int sock; +struct sockaddr_in gcAddr; +struct sockaddr_in locAddr; +uint8_t buf[BUFFER_LENGTH]; +ssize_t recsize; +socklen_t fromlen; +int bytes_sent; +mavlink_message_t msg; +uint16_t len; +int i = 0; +unsigned int temp = 0; + +uint64_t microsSinceEpoch(); + + +int main(int argc, char* argv[]) +{ + // Initialize MAVLink + mavlink_wpm_init(&wpm); + mavlink_system.sysid = 1; + mavlink_system.compid = MAV_COMP_ID_WAYPOINTPLANNER; + + + + // Create socket + sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); + + // Check if --help flag was used + if ((argc == 2) && (strcmp(argv[1], help) == 0)) + { + printf("\n"); + printf("\tUsage:\n\n"); + printf("\t"); + printf("%s", argv[0]); + printf(" \n"); + printf("\tDefault for localhost: udp-server 127.0.0.1\n\n"); + exit(EXIT_FAILURE); + } + + + // Change the target ip if parameter was given + strcpy(target_ip, "127.0.0.1"); + if (argc == 2) + { + strcpy(target_ip, argv[1]); + } + + + memset(&locAddr, 0, sizeof(locAddr)); + locAddr.sin_family = AF_INET; + locAddr.sin_addr.s_addr = INADDR_ANY; + locAddr.sin_port = htons(14551); + + /* Bind the socket to port 14551 - necessary to receive packets from qgroundcontrol */ + if (-1 == bind(sock,(struct sockaddr *)&locAddr, sizeof(struct sockaddr))) + { + perror("error bind failed"); + close(sock); + exit(EXIT_FAILURE); + } + + /* Attempt to make it non blocking */ + if (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0) + { + fprintf(stderr, "error setting nonblocking: %s\n", strerror(errno)); + close(sock); + exit(EXIT_FAILURE); + } + + + memset(&gcAddr, 0, sizeof(gcAddr)); + gcAddr.sin_family = AF_INET; + gcAddr.sin_addr.s_addr = inet_addr(target_ip); + gcAddr.sin_port = htons(14550); + + + printf("MAVLINK MISSION LIBRARY EXAMPLE PROCESS INITIALIZATION DONE, RUNNING..\n"); + + + for (;;) + { + + /*Send Heartbeat */ + mavlink_msg_heartbeat_pack(mavlink_system.sysid, 200, &msg, MAV_TYPE_HELICOPTER, MAV_CLASS_GENERIC); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + /* Send Status */ + mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED, MAV_NAV_HOLD, MAV_STATE_ACTIVE, 500, 7500, 0, 0); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in)); + + /* Send Local Position */ + mavlink_msg_local_position_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), + position[0], position[1], position[2], + position[3], position[4], position[5]); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + /* Send attitude */ + mavlink_msg_attitude_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + + memset(buf, 0, BUFFER_LENGTH); + recsize = recvfrom(sock, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&gcAddr, &fromlen); + if (recsize > 0) + { + // Something received - print out all bytes and parse packet + mavlink_message_t msg; + mavlink_status_t status; + + printf("Bytes Received: %d\nDatagram: ", (int)recsize); + for (i = 0; i < recsize; ++i) + { + temp = buf[i]; + printf("%02x ", (unsigned char)temp); + if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status)) + { + // Packet received + printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid); + + // Handle packet with waypoint component + mavlink_wpm_message_handler(&msg); + + // Handle packet with parameter component + } + } + printf("\n"); + } + memset(buf, 0, BUFFER_LENGTH); + sleep(1); // Sleep one second + } +} + + +/* QNX timer version */ +#if (defined __QNX__) | (defined __QNXNTO__) +uint64_t microsSinceEpoch() +{ + + struct timespec time; + + uint64_t micros = 0; + + clock_gettime(CLOCK_REALTIME, &time); + micros = (uint64_t)time.tv_sec * 100000 + time.tv_nsec/1000; + + return micros; +} +#else +uint64_t microsSinceEpoch() +{ + + struct timeval tv; + + uint64_t micros = 0; + + gettimeofday(&tv, NULL); + micros = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; + + return micros; +} +#endif \ No newline at end of file diff --git a/libraries/GCS_MAVLink/missionlib/testing/udp.c b/libraries/GCS_MAVLink/missionlib/testing/udp.c new file mode 100644 index 0000000000..dc096be51b --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/udp.c @@ -0,0 +1,1073 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + and Bryan Godbolt godbolt ( a t ) ualberta.ca + + adapted from example written by Bryan Godbolt godbolt ( a t ) ualberta.ca + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + + ****************************************************************************/ +/* + This program sends some data to qgroundcontrol using the mavlink protocol. The sent packets + cause qgroundcontrol to respond with heartbeats. Any settings or custom commands sent from + qgroundcontrol are printed by this program along with the heartbeats. + + + I compiled this program sucessfully on Ubuntu 10.04 with the following command + + gcc -I ../../pixhawk/mavlink/include -o udp-server udp.c + + the rt library is needed for the clock_gettime on linux + */ +/* These headers are for QNX, but should all be standard on unix/linux */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if (defined __QNX__) | (defined __QNXNTO__) +/* QNX specific headers */ +#include +#else +/* Linux / MacOS POSIX timer headers */ +#include +#include +#include +#endif + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ +#include + + +#define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why) + +uint64_t microsSinceEpoch(); + + +// FIXME XXX - TO BE MOVED TO XML +enum MAVLINK_WPM_STATES +{ + MAVLINK_WPM_STATE_IDLE = 0, + MAVLINK_WPM_STATE_SENDLIST, + MAVLINK_WPM_STATE_SENDLIST_SENDWPS, + MAVLINK_WPM_STATE_GETLIST, + MAVLINK_WPM_STATE_GETLIST_GETWPS, + MAVLINK_WPM_STATE_GETLIST_GOTALL, + MAVLINK_WPM_STATE_ENUM_END +}; + +enum MAVLINK_WPM_CODES +{ + MAVLINK_WPM_CODE_OK = 0, + MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS, + MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, + MAVLINK_WPM_CODE_ENUM_END +}; + + +/* WAYPOINT MANAGER - MISSION LIB */ + +#define MAVLINK_WPM_MAX_WP_COUNT 100 +#define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates +#define MAVLINK_WPM_TEXT_FEEDBACK ///< Report back status information as text +#define MAVLINK_WPM_SYSTEM_ID 1 +#define MAVLINK_WPM_COMPONENT_ID 1 + +struct _mavlink_wpm_storage { + mavlink_waypoint_t waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Currently active waypoints +#ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE + mavlink_waypoint_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints +#endif + uint16_t count; + MAVLINK_WPM_STATES current_state; +} mavlink_wpm_storage; + + +void mavlink_wpm_init(mavlink_wpm_storage* state) +{ + // Set all waypoints to zero + + // Set count to zero + state->count = 0; + state->current_state = MAVLINK_WPM_STATE_IDLE; +} + + +PX_WAYPOINTPLANNER_STATES current_state = PX_WPP_IDLE; +uint16_t protocol_current_wp_id = 0; +uint16_t protocol_current_count = 0; +uint8_t protocol_current_partner_systemid = 0; +uint8_t protocol_current_partner_compid = 0; +uint64_t protocol_timestamp_lastaction = 0; + +uint64_t timestamp_last_send_setpoint = 0; + + +/* + * @brief Sends an waypoint ack message + */ +void mavlink_wpm_send_waypoint_ack(uint8_t target_systemid, uint8_t target_compid, uint8_t type) +{ + mavlink_message_t msg; + mavlink_waypoint_ack_t wpa; + + wpa.target_system = target_systemid; + wpa.target_component = target_compid; + wpa.type = type; + + mavlink_msg_waypoint_ack_encode(systemid, compid, &msg, &wpa); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); + + if (verbose) printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system); +} + +/* + * @brief Broadcasts the new target waypoint and directs the MAV to fly there + * + * This function broadcasts its new active waypoint sequence number and + * sends a message to the controller, advising it to fly to the coordinates + * of the waypoint with a given orientation + * + * @param seq The waypoint sequence number the MAV should fly to. + */ +void mavlink_wpm_send_waypoint_current(uint16_t seq) +{ + if(seq < waypoints->size()) + { + mavlink_waypoint_t *cur = waypoints->at(seq); + + mavlink_message_t msg; + mavlink_waypoint_current_t wpc; + + wpc.seq = cur->seq; + + mavlink_msg_waypoint_current_encode(systemid, compid, &msg, &wpc); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); + + if (verbose) printf("Broadcasted new current waypoint %u\n", wpc.seq); + } + else + { + if (verbose) printf("ERROR: index out of bounds\n"); + } +} + +/* + * @brief Directs the MAV to fly to a position + * + * Sends a message to the controller, advising it to fly to the coordinates + * of the waypoint with a given orientation + * + * @param seq The waypoint sequence number the MAV should fly to. + */ +void mavlink_wpm_send_setpoint(uint16_t seq) +{ + if(seq < waypoints->size()) + { + mavlink_waypoint_t *cur = waypoints->at(seq); + + mavlink_message_t msg; + mavlink_local_position_setpoint_set_t PControlSetPoint; + + // send new set point to local IMU + if (cur->frame == 1) + { + PControlSetPoint.target_system = systemid; + PControlSetPoint.target_component = MAV_COMP_ID_IMU; + PControlSetPoint.x = cur->x; + PControlSetPoint.y = cur->y; + PControlSetPoint.z = cur->z; + PControlSetPoint.yaw = cur->param4; + + mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (verbose) printf("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq); + } + + struct timeval tv; + gettimeofday(&tv, NULL); + uint64_t now = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; + timestamp_last_send_setpoint = now; + } + else + { + if (verbose) printf("ERROR: index out of bounds\n"); + } +} + +void mavlink_wpm_send_waypoint_count(uint8_t target_systemid, uint8_t target_compid, uint16_t count) +{ + mavlink_message_t msg; + mavlink_waypoint_count_t wpc; + + wpc.target_system = target_systemid; + wpc.target_component = target_compid; + wpc.count = count; + + mavlink_msg_waypoint_count_encode(systemid, compid, &msg, &wpc); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + + if (verbose) printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); +} + +void mavlink_wpm_send_waypoint(uint8_t target_systemid, uint8_t target_compid, uint16_t seq) +{ + if (seq < waypoints->size()) + { + mavlink_message_t msg; + mavlink_waypoint_t *wp = waypoints->at(seq); + wp->target_system = target_systemid; + wp->target_component = target_compid; + mavlink_msg_waypoint_encode(systemid, compid, &msg, wp); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + if (verbose) printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (verbose) printf("ERROR: index out of bounds\n"); + } +} + +void mavlink_wpm_send_waypoint_request(uint8_t target_systemid, uint8_t target_compid, uint16_t seq) +{ + if (seq < waypoints->size()) + { + mavlink_message_t msg; + mavlink_waypoint_request_t wpr; + wpr.target_system = target_systemid; + wpr.target_component = target_compid; + wpr.seq = seq; + mavlink_msg_waypoint_request_encode(systemid, compid, &msg, &wpr); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + if (verbose) printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (verbose) printf("ERROR: index out of bounds\n"); + } +} + +/* + * @brief emits a message that a waypoint reached + * + * This function broadcasts a message that a waypoint is reached. + * + * @param seq The waypoint sequence number the MAV has reached. + */ +void mavlink_wpm_send_waypoint_reached(uint16_t seq) +{ + mavlink_message_t msg; + mavlink_waypoint_reached_t wp_reached; + + wp_reached.seq = seq; + + mavlink_msg_waypoint_reached_encode(systemid, compid, &msg, &wp_reached); + mavlink_message_t_publish(lcm, "MAVLINK", &msg); + + if (verbose) printf("Sent waypoint %u reached message\n", wp_reached.seq); + + usleep(paramClient->getParamValue("PROTOCOLDELAY")); +} + +float mavlink_wpm_distance_to_segment(uint16_t seq, float x, float y, float z) +{ + if (seq < waypoints->size()) + { + mavlink_waypoint_t *cur = waypoints->at(seq); + + const PxVector3 A(cur->x, cur->y, cur->z); + const PxVector3 C(x, y, z); + + // seq not the second last waypoint + if ((uint16_t)(seq+1) < waypoints->size()) + { + mavlink_waypoint_t *next = waypoints->at(seq+1); + const PxVector3 B(next->x, next->y, next->z); + const float r = (B-A).dot(C-A) / (B-A).lengthSquared(); + if (r >= 0 && r <= 1) + { + const PxVector3 P(A + r*(B-A)); + return (P-C).length(); + } + else if (r < 0.f) + { + return (C-A).length(); + } + else + { + return (C-B).length(); + } + } + else + { + return (C-A).length(); + } + } + else + { + if (verbose) printf("ERROR: index out of bounds\n"); + } + return -1.f; +} + +float mavlink_wpm_distance_to_point(uint16_t seq, float x, float y, float z) +{ + if (seq < waypoints->size()) + { + mavlink_waypoint_t *cur = waypoints->at(seq); + + const PxVector3 A(cur->x, cur->y, cur->z); + const PxVector3 C(x, y, z); + + return (C-A).length(); + } + else + { + if (verbose) printf("ERROR: index out of bounds\n"); + } + return -1.f; +} + + +static void mavlink_wpm_mavlink_handler(const lcm_recv_buf_t *rbuf, const char * channel, const mavlink_message_t* msg, void * user) +{ + // Handle param messages + paramClient->handleMAVLinkPacket(msg); + + //check for timed-out operations + struct timeval tv; + gettimeofday(&tv, NULL); + uint64_t now = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; + if (now-protocol_timestamp_lastaction > paramClient->getParamValue("PROTOCOLTIMEOUT") && current_state != PX_WPP_IDLE) + { + if (verbose) printf("Last operation (state=%u) timed out, changing state to PX_WPP_IDLE\n", current_state); + current_state = PX_WPP_IDLE; + protocol_current_count = 0; + protocol_current_partner_systemid = 0; + protocol_current_partner_compid = 0; + protocol_current_wp_id = -1; + + if(waypoints->size() == 0) + { + current_active_wp_id = -1; + } + } + + if(now-timestamp_last_send_setpoint > paramClient->getParamValue("SETPOINTDELAY") && current_active_wp_id < waypoints->size()) + { + send_setpoint(current_active_wp_id); + } + + switch(msg->msgid) + { + case MAVLINK_MSG_ID_ATTITUDE: + { + if(msg->sysid == systemid && current_active_wp_id < waypoints->size()) + { + mavlink_waypoint_t *wp = waypoints->at(current_active_wp_id); + if(wp->frame == 1) + { + mavlink_attitude_t att; + mavlink_msg_attitude_decode(msg, &att); + float yaw_tolerance = paramClient->getParamValue("YAWTOLERANCE"); + //compare current yaw + if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI) + { + if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4) + yawReached = true; + } + else if(att.yaw - yaw_tolerance < 0.0f) + { + float lowerBound = 360.0f + att.yaw - yaw_tolerance; + if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance) + yawReached = true; + } + else + { + float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI; + if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound) + yawReached = true; + } + } + } + break; + } + + case MAVLINK_MSG_ID_LOCAL_POSITION: + { + if(msg->sysid == systemid && current_active_wp_id < waypoints->size()) + { + mavlink_waypoint_t *wp = waypoints->at(current_active_wp_id); + + if(wp->frame == 1) + { + mavlink_local_position_t pos; + mavlink_msg_local_position_decode(msg, &pos); + if (debug) printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z); + + posReached = false; + + // compare current position (given in message) with current waypoint + float orbit = wp->param1; + + float dist; + if (wp->param2 == 0) + { + dist = distanceToSegment(current_active_wp_id, pos.x, pos.y, pos.z); + } + else + { + dist = distanceToPoint(current_active_wp_id, pos.x, pos.y, pos.z); + } + + if (dist >= 0.f && dist <= orbit && yawReached) + { + posReached = true; + } + } + } + break; + } + + case MAVLINK_MSG_ID_CMD: // special action from ground station + { + mavlink_cmd_t action; + mavlink_msg_cmd_decode(msg, &action); + if(action.target == systemid) + { + if (verbose) std::cerr << "Waypoint: received message with action " << action.action << std::endl; + switch (action.action) + { + // case MAV_ACTION_LAUNCH: + // if (verbose) std::cerr << "Launch received" << std::endl; + // current_active_wp_id = 0; + // if (waypoints->size()>0) + // { + // setActive(waypoints[current_active_wp_id]); + // } + // else + // if (verbose) std::cerr << "No launch, waypointList empty" << std::endl; + // break; + + // case MAV_ACTION_CONTINUE: + // if (verbose) std::c + // err << "Continue received" << std::endl; + // idle = false; + // setActive(waypoints[current_active_wp_id]); + // break; + + // case MAV_ACTION_HALT: + // if (verbose) std::cerr << "Halt received" << std::endl; + // idle = true; + // break; + + // default: + // if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl; + // break; + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_ACK: + { + mavlink_waypoint_ack_t wpa; + mavlink_msg_waypoint_ack_decode(msg, &wpa); + + if((msg->sysid == protocol_current_partner_systemid && msg->compid == protocol_current_partner_compid) && (wpa.target_system == systemid && wpa.target_component == compid)) + { + protocol_timestamp_lastaction = now; + + if (current_state == PX_WPP_SENDLIST || current_state == PX_WPP_SENDLIST_SENDWPS) + { + if (protocol_current_wp_id == waypoints->size()-1) + { + if (verbose) printf("Received Ack after having sent last waypoint, going to state PX_WPP_IDLE\n"); + current_state = PX_WPP_IDLE; + protocol_current_wp_id = 0; + } + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: + { + mavlink_waypoint_set_current_t wpc; + mavlink_msg_waypoint_set_current_decode(msg, &wpc); + + if(wpc.target_system == systemid && wpc.target_component == compid) + { + protocol_timestamp_lastaction = now; + + if (current_state == PX_WPP_IDLE) + { + if (wpc.seq < waypoints->size()) + { + if (verbose) printf("Received MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT\n"); + current_active_wp_id = wpc.seq; + uint32_t i; + for(i = 0; i < waypoints->size(); i++) + { + if (i == current_active_wp_id) + { + waypoints->at(i)->current = true; + } + else + { + waypoints->at(i)->current = false; + } + } + if (verbose) printf("New current waypoint %u\n", current_active_wp_id); + yawReached = false; + posReached = false; + send_waypoint_current(current_active_wp_id); + send_setpoint(current_active_wp_id); + timestamp_firstinside_orbit = 0; + } + else + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: Index out of bounds\n"); + } + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: + { + mavlink_waypoint_request_list_t wprl; + mavlink_msg_waypoint_request_list_decode(msg, &wprl); + if(wprl.target_system == systemid && wprl.target_component == compid) + { + protocol_timestamp_lastaction = now; + + if (current_state == PX_WPP_IDLE || current_state == PX_WPP_SENDLIST) + { + if (waypoints->size() > 0) + { + if (verbose && current_state == PX_WPP_IDLE) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u changing state to PX_WPP_SENDLIST\n", msg->sysid); + if (verbose && current_state == PX_WPP_SENDLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST again from %u staying in state PX_WPP_SENDLIST\n", msg->sysid); + current_state = PX_WPP_SENDLIST; + protocol_current_wp_id = 0; + protocol_current_partner_systemid = msg->sysid; + protocol_current_partner_compid = msg->compid; + } + else + { + if (verbose) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid); + } + protocol_current_count = waypoints->size(); + send_waypoint_count(msg->sysid,msg->compid, protocol_current_count); + } + else + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST because i'm doing something else already (state=%i).\n", current_state); + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST: + { + mavlink_waypoint_request_t wpr; + mavlink_msg_waypoint_request_decode(msg, &wpr); + if(msg->sysid == protocol_current_partner_systemid && msg->compid == protocol_current_partner_compid && wpr.target_system == systemid && wpr.target_component == compid) + { + protocol_timestamp_lastaction = now; + + //ensure that we are in the correct state and that the first request has id 0 and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint) + if ((current_state == PX_WPP_SENDLIST && wpr.seq == 0) || (current_state == PX_WPP_SENDLIST_SENDWPS && (wpr.seq == protocol_current_wp_id || wpr.seq == protocol_current_wp_id + 1) && wpr.seq < waypoints->size())) + { + if (verbose && current_state == PX_WPP_SENDLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u changing state to PX_WPP_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (verbose && current_state == PX_WPP_SENDLIST_SENDWPS && wpr.seq == protocol_current_wp_id + 1) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u staying in state PX_WPP_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (verbose && current_state == PX_WPP_SENDLIST_SENDWPS && wpr.seq == protocol_current_wp_id) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u (again) from %u staying in state PX_WPP_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + + current_state = PX_WPP_SENDLIST_SENDWPS; + protocol_current_wp_id = wpr.seq; + send_waypoint(protocol_current_partner_systemid, protocol_current_partner_compid, wpr.seq); + } + else + { + if (verbose) + { + if (!(current_state == PX_WPP_SENDLIST || current_state == PX_WPP_SENDLIST_SENDWPS)) { printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because i'm doing something else already (state=%i).\n", current_state); break; } + else if (current_state == PX_WPP_SENDLIST) + { + if (wpr.seq != 0) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq); + } + else if (current_state == PX_WPP_SENDLIST_SENDWPS) + { + if (wpr.seq != protocol_current_wp_id && wpr.seq != protocol_current_wp_id + 1) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, protocol_current_wp_id, protocol_current_wp_id+1); + else if (wpr.seq >= waypoints->size()) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq); + } + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST - FIXME: missed error description\n"); + } + } + } + else + { + //we we're target but already communicating with someone else + if((wpr.target_system == systemid && wpr.target_component == compid) && !(msg->sysid == protocol_current_partner_systemid && msg->compid == protocol_current_partner_compid)) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, protocol_current_partner_systemid); + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_COUNT: + { + mavlink_waypoint_count_t wpc; + mavlink_msg_waypoint_count_decode(msg, &wpc); + if(wpc.target_system == systemid && wpc.target_component == compid) + { + protocol_timestamp_lastaction = now; + + if (current_state == PX_WPP_IDLE || (current_state == PX_WPP_GETLIST && protocol_current_wp_id == 0)) + { + if (wpc.count > 0) + { + if (verbose && current_state == PX_WPP_IDLE) printf("Got MAVLINK_MSG_ID_WAYPOINT_COUNT (%u) from %u changing state to PX_WPP_GETLIST\n", wpc.count, msg->sysid); + if (verbose && current_state == PX_WPP_GETLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT_COUNT (%u) again from %u\n", wpc.count, msg->sysid); + + current_state = PX_WPP_GETLIST; + protocol_current_wp_id = 0; + protocol_current_partner_systemid = msg->sysid; + protocol_current_partner_compid = msg->compid; + protocol_current_count = wpc.count; + + printf("clearing receive buffer and readying for receiving waypoints\n"); + while(waypoints_receive_buffer->size() > 0) + { + delete waypoints_receive_buffer->back(); + waypoints_receive_buffer->pop_back(); + } + + send_waypoint_request(protocol_current_partner_systemid, protocol_current_partner_compid, protocol_current_wp_id); + } + else if (wpc.count == 0) + { + printf("got waypoint count of 0, clearing waypoint list and staying in state PX_WPP_IDLE\n"); + while(waypoints_receive_buffer->size() > 0) + { + delete waypoints->back(); + waypoints->pop_back(); + } + current_active_wp_id = -1; + yawReached = false; + posReached = false; + break; + + } + else + { + if (verbose) printf("Ignoring MAVLINK_MSG_ID_WAYPOINT_COUNT from %u with count of %u\n", msg->sysid, wpc.count); + } + } + else + { + if (verbose && !(current_state == PX_WPP_IDLE || current_state == PX_WPP_GETLIST)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT because i'm doing something else already (state=%i).\n", current_state); + else if (verbose && current_state == PX_WPP_GETLIST && protocol_current_wp_id != 0) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT because i'm already receiving waypoint %u.\n", protocol_current_wp_id); + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT - FIXME: missed error description\n"); + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT: + { + mavlink_waypoint_t wp; + mavlink_msg_waypoint_decode(msg, &wp); + + if((msg->sysid == protocol_current_partner_systemid && msg->compid == protocol_current_partner_compid) && (wp.target_system == systemid && wp.target_component == compid)) + { + protocol_timestamp_lastaction = now; + + //ensure that we are in the correct state and that the first waypoint has id 0 and the following waypoints have the correct ids + if ((current_state == PX_WPP_GETLIST && wp.seq == 0) || (current_state == PX_WPP_GETLIST_GETWPS && wp.seq == protocol_current_wp_id && wp.seq < protocol_current_count)) + { + if (verbose && current_state == PX_WPP_GETLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u changing state to PX_WPP_GETLIST_GETWPS\n", wp.seq, msg->sysid); + if (verbose && current_state == PX_WPP_GETLIST_GETWPS && wp.seq == protocol_current_wp_id) printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u\n", wp.seq, msg->sysid); + if (verbose && current_state == PX_WPP_GETLIST_GETWPS && wp.seq-1 == protocol_current_wp_id) printf("Got MAVLINK_MSG_ID_WAYPOINT %u (again) from %u\n", wp.seq, msg->sysid); + + current_state = PX_WPP_GETLIST_GETWPS; + protocol_current_wp_id = wp.seq + 1; + mavlink_waypoint_t* newwp = new mavlink_waypoint_t; + memcpy(newwp, &wp, sizeof(mavlink_waypoint_t)); + waypoints_receive_buffer->push_back(newwp); + + if (verbose) printf ("Added new waypoint to list. X= %f\t Y= %f\t Z= %f\t Yaw= %f\n", newwp->x, newwp->y, newwp->z, newwp->param4); + + if(protocol_current_wp_id == protocol_current_count && current_state == PX_WPP_GETLIST_GETWPS) + { + if (verbose) printf("Got all %u waypoints, changing state to PX_WPP_IDLE\n", protocol_current_count); + + send_waypoint_ack(protocol_current_partner_systemid, protocol_current_partner_compid, 0); + + if (current_active_wp_id > waypoints_receive_buffer->size()-1) + { + current_active_wp_id = waypoints_receive_buffer->size() - 1; + } + + // switch the waypoints list + std::vector* waypoints_temp = waypoints; + waypoints = waypoints_receive_buffer; + waypoints_receive_buffer = waypoints_temp; + + //get the new current waypoint + uint32_t i; + for(i = 0; i < waypoints->size(); i++) + { + if (waypoints->at(i)->current == 1) + { + current_active_wp_id = i; + //if (verbose) printf("New current waypoint %u\n", current_active_wp_id); + yawReached = false; + posReached = false; + send_waypoint_current(current_active_wp_id); + send_setpoint(current_active_wp_id); + timestamp_firstinside_orbit = 0; + break; + } + } + + if (i == waypoints->size()) + { + current_active_wp_id = -1; + yawReached = false; + posReached = false; + timestamp_firstinside_orbit = 0; + } + + current_state = PX_WPP_IDLE; + } + else + { + send_waypoint_request(protocol_current_partner_systemid, protocol_current_partner_compid, protocol_current_wp_id); + } + } + else + { + if (current_state == PX_WPP_IDLE) + { + //we're done receiving waypoints, answer with ack. + send_waypoint_ack(protocol_current_partner_systemid, protocol_current_partner_compid, 0); + printf("Received MAVLINK_MSG_ID_WAYPOINT while state=PX_WPP_IDLE, answered with WAYPOINT_ACK.\n"); + } + if (verbose) + { + if (!(current_state == PX_WPP_GETLIST || current_state == PX_WPP_GETLIST_GETWPS)) { printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u because i'm doing something else already (state=%i).\n", wp.seq, current_state); break; } + else if (current_state == PX_WPP_GETLIST) + { + if(!(wp.seq == 0)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the first waypoint ID (%u) was not 0.\n", wp.seq); + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + } + else if (current_state == PX_WPP_GETLIST_GETWPS) + { + if (!(wp.seq == protocol_current_wp_id)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the waypoint ID (%u) was not the expected %u.\n", wp.seq, protocol_current_wp_id); + else if (!(wp.seq < protocol_current_count)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the waypoint ID (%u) was out of bounds.\n", wp.seq); + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + } + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + } + } + } + else + { + //we we're target but already communicating with someone else + if((wp.target_system == systemid && wp.target_component == compid) && !(msg->sysid == protocol_current_partner_systemid && msg->compid == protocol_current_partner_compid) && current_state != PX_WPP_IDLE) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, protocol_current_partner_systemid); + } + else if(wp.target_system == systemid && wp.target_component == compid) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid); + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: + { + mavlink_waypoint_clear_all_t wpca; + mavlink_msg_waypoint_clear_all_decode(msg, &wpca); + + if(wpca.target_system == systemid && wpca.target_component == compid && current_state == PX_WPP_IDLE) + { + protocol_timestamp_lastaction = now; + + if (verbose) printf("Got MAVLINK_MSG_ID_WAYPOINT_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid); + while(waypoints->size() > 0) + { + delete waypoints->back(); + waypoints->pop_back(); + } + current_active_wp_id = -1; + yawReached = false; + posReached = false; + } + else if (wpca.target_system == systemid && wpca.target_component == compid && current_state != PX_WPP_IDLE) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, current_state); + } + break; + } + + default: + { + if (debug) std::cerr << "Waypoint: received message of unknown type" << std::endl; + break; + } + } + + //check if the current waypoint was reached + if ((posReached && /*yawReached &&*/ !idle)) + { + if (current_active_wp_id < waypoints->size()) + { + mavlink_waypoint_t *cur_wp = waypoints->at(current_active_wp_id); + + if (timestamp_firstinside_orbit == 0) + { + // Announce that last waypoint was reached + if (verbose) printf("*** Reached waypoint %u ***\n", cur_wp->seq); + send_waypoint_reached(cur_wp->seq); + timestamp_firstinside_orbit = now; + } + + // check if the MAV was long enough inside the waypoint orbit + //if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000)) + if(now-timestamp_firstinside_orbit >= cur_wp->param2*1000) + { + if (cur_wp->autocontinue) + { + cur_wp->current = 0; + if (current_active_wp_id == waypoints->size() - 1 && waypoints->size() > 1) + { + //the last waypoint was reached, if auto continue is + //activated restart the waypoint list from the beginning + current_active_wp_id = 1; + } + else + { + if ((uint16_t)(current_active_wp_id + 1) < waypoints->size()) + current_active_wp_id++; + } + + // Fly to next waypoint + timestamp_firstinside_orbit = 0; + send_waypoint_current(current_active_wp_id); + send_setpoint(current_active_wp_id); + waypoints->at(current_active_wp_id)->current = true; + posReached = false; + yawReached = false; + if (verbose) printf("Set new waypoint (%u)\n", current_active_wp_id); + } + } + } + } + else + { + timestamp_lastoutside_orbit = now; + } +} + + + + + + + + +int main(int argc, char* argv[]) +{ + + char help[] = "--help"; + + + char target_ip[100]; + + float position[6] = {}; + int sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); + struct sockaddr_in gcAddr; + struct sockaddr_in locAddr; + //struct sockaddr_in fromAddr; + uint8_t buf[BUFFER_LENGTH]; + ssize_t recsize; + socklen_t fromlen; + int bytes_sent; + mavlink_message_t msg; + uint16_t len; + int i = 0; + //int success = 0; + unsigned int temp = 0; + + // Check if --help flag was used + if ((argc == 2) && (strcmp(argv[1], help) == 0)) + { + printf("\n"); + printf("\tUsage:\n\n"); + printf("\t"); + printf("%s", argv[0]); + printf(" \n"); + printf("\tDefault for localhost: udp-server 127.0.0.1\n\n"); + exit(EXIT_FAILURE); + } + + + // Change the target ip if parameter was given + strcpy(target_ip, "127.0.0.1"); + if (argc == 2) + { + strcpy(target_ip, argv[1]); + } + + + memset(&locAddr, 0, sizeof(locAddr)); + locAddr.sin_family = AF_INET; + locAddr.sin_addr.s_addr = INADDR_ANY; + locAddr.sin_port = htons(14551); + + /* Bind the socket to port 14551 - necessary to receive packets from qgroundcontrol */ + if (-1 == bind(sock,(struct sockaddr *)&locAddr, sizeof(struct sockaddr))) + { + perror("error bind failed"); + close(sock); + exit(EXIT_FAILURE); + } + + /* Attempt to make it non blocking */ + if (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0) + { + fprintf(stderr, "error setting nonblocking: %s\n", strerror(errno)); + close(sock); + exit(EXIT_FAILURE); + } + + + memset(&gcAddr, 0, sizeof(gcAddr)); + gcAddr.sin_family = AF_INET; + gcAddr.sin_addr.s_addr = inet_addr(target_ip); + gcAddr.sin_port = htons(14550); + + + printf("MAVLINK MISSION LIBRARY EXAMPLE PROCESS INITIALIZATION DONE, RUNNING..\n"); + + + for (;;) + { + + /*Send Heartbeat */ + mavlink_msg_heartbeat_pack(1, 200, &msg, MAV_TYPE_HELICOPTER, MAV_CLASS_GENERIC); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + /* Send Status */ + mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED, MAV_NAV_HOLD, MAV_STATE_ACTIVE, 500, 7500, 0, 0); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in)); + + /* Send Local Position */ + mavlink_msg_local_position_pack(1, 200, &msg, microsSinceEpoch(), + position[0], position[1], position[2], + position[3], position[4], position[5]); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + /* Send attitude */ + mavlink_msg_attitude_pack(1, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + + memset(buf, 0, BUFFER_LENGTH); + recsize = recvfrom(sock, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&gcAddr, &fromlen); + if (recsize > 0) + { + // Something received - print out all bytes and parse packet + mavlink_message_t msg; + mavlink_status_t status; + + printf("Bytes Received: %d\nDatagram: ", (int)recsize); + for (i = 0; i < recsize; ++i) + { + temp = buf[i]; + printf("%02x ", (unsigned char)temp); + if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status)) + { + // Packet received + printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid); + } + } + printf("\n"); + } + memset(buf, 0, BUFFER_LENGTH); + sleep(1); // Sleep one second + } +} + + +/* QNX timer version */ +#if (defined __QNX__) | (defined __QNXNTO__) +uint64_t microsSinceEpoch() +{ + + struct timespec time; + + uint64_t micros = 0; + + clock_gettime(CLOCK_REALTIME, &time); + micros = (uint64_t)time.tv_sec * 100000 + time.tv_nsec/1000; + + return micros; +} +#else +uint64_t microsSinceEpoch() +{ + + struct timeval tv; + + uint64_t micros = 0; + + gettimeofday(&tv, NULL); + micros = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; + + return micros; +} +#endif \ No newline at end of file diff --git a/libraries/GCS_MAVLink/missionlib/testing/udptest.1 b/libraries/GCS_MAVLink/missionlib/testing/udptest.1 new file mode 100644 index 0000000000..78b31915f7 --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/udptest.1 @@ -0,0 +1,79 @@ +.\"Modified from man(1) of FreeBSD, the NetBSD mdoc.template, and mdoc.samples. +.\"See Also: +.\"man mdoc.samples for a complete listing of options +.\"man mdoc for the short list of editing options +.\"/usr/share/misc/mdoc.template +.Dd 01.08.11 \" DATE +.Dt udptest 1 \" Program name and manual section number +.Os Darwin +.Sh NAME \" Section Header - required - don't modify +.Nm udptest, +.\" The following lines are read in generating the apropos(man -k) database. Use only key +.\" words here as the database is built based on the words here and in the .ND line. +.Nm Other_name_for_same_program(), +.Nm Yet another name for the same program. +.\" Use .Nm macro to designate other names for the documented program. +.Nd This line parsed for whatis database. +.Sh SYNOPSIS \" Section Header - required - don't modify +.Nm +.Op Fl abcd \" [-abcd] +.Op Fl a Ar path \" [-a path] +.Op Ar file \" [file] +.Op Ar \" [file ...] +.Ar arg0 \" Underlined argument - use .Ar anywhere to underline +arg2 ... \" Arguments +.Sh DESCRIPTION \" Section Header - required - don't modify +Use the .Nm macro to refer to your program throughout the man page like such: +.Nm +Underlining is accomplished with the .Ar macro like this: +.Ar underlined text . +.Pp \" Inserts a space +A list of items with descriptions: +.Bl -tag -width -indent \" Begins a tagged list +.It item a \" Each item preceded by .It macro +Description of item a +.It item b +Description of item b +.El \" Ends the list +.Pp +A list of flags and their descriptions: +.Bl -tag -width -indent \" Differs from above in tag removed +.It Fl a \"-a flag as a list item +Description of -a flag +.It Fl b +Description of -b flag +.El \" Ends the list +.Pp +.\" .Sh ENVIRONMENT \" May not be needed +.\" .Bl -tag -width "ENV_VAR_1" -indent \" ENV_VAR_1 is width of the string ENV_VAR_1 +.\" .It Ev ENV_VAR_1 +.\" Description of ENV_VAR_1 +.\" .It Ev ENV_VAR_2 +.\" Description of ENV_VAR_2 +.\" .El +.Sh FILES \" File used or created by the topic of the man page +.Bl -tag -width "/Users/joeuser/Library/really_long_file_name" -compact +.It Pa /usr/share/file_name +FILE_1 description +.It Pa /Users/joeuser/Library/really_long_file_name +FILE_2 description +.El \" Ends the list +.\" .Sh DIAGNOSTICS \" May not be needed +.\" .Bl -diag +.\" .It Diagnostic Tag +.\" Diagnostic informtion here. +.\" .It Diagnostic Tag +.\" Diagnostic informtion here. +.\" .El +.Sh SEE ALSO +.\" List links in ascending order by section, alphabetically within a section. +.\" Please do not reference files that do not exist without filing a bug report +.Xr a 1 , +.Xr b 1 , +.Xr c 1 , +.Xr a 2 , +.Xr b 2 , +.Xr a 3 , +.Xr b 3 +.\" .Sh BUGS \" Document known, unremedied bugs +.\" .Sh HISTORY \" Document history if command behaves in a unique manner \ No newline at end of file diff --git a/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/project.pbxproj b/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/project.pbxproj new file mode 100644 index 0000000000..1dc88f3c65 --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/project.pbxproj @@ -0,0 +1,211 @@ +// !$*UTF8*$! +{ + archiveVersion = 1; + classes = { + }; + objectVersion = 45; + objects = { + +/* Begin PBXBuildFile section */ + 8DD76FAC0486AB0100D96B5E /* main.c in Sources */ = {isa = PBXBuildFile; fileRef = 08FB7796FE84155DC02AAC07 /* main.c */; settings = {ATTRIBUTES = (); }; }; + 8DD76FB00486AB0100D96B5E /* udptest.1 in CopyFiles */ = {isa = PBXBuildFile; fileRef = C6A0FF2C0290799A04C91782 /* udptest.1 */; }; +/* End PBXBuildFile section */ + +/* Begin PBXCopyFilesBuildPhase section */ + 8DD76FAF0486AB0100D96B5E /* CopyFiles */ = { + isa = PBXCopyFilesBuildPhase; + buildActionMask = 8; + dstPath = /usr/share/man/man1/; + dstSubfolderSpec = 0; + files = ( + 8DD76FB00486AB0100D96B5E /* udptest.1 in CopyFiles */, + ); + runOnlyForDeploymentPostprocessing = 1; + }; +/* End PBXCopyFilesBuildPhase section */ + +/* Begin PBXFileReference section */ + 08FB7796FE84155DC02AAC07 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 8DD76FB20486AB0100D96B5E /* udptest */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = udptest; sourceTree = BUILT_PRODUCTS_DIR; }; + C6A0FF2C0290799A04C91782 /* udptest.1 */ = {isa = PBXFileReference; lastKnownFileType = text.man; path = udptest.1; sourceTree = ""; }; +/* End PBXFileReference section */ + +/* Begin PBXFrameworksBuildPhase section */ + 8DD76FAD0486AB0100D96B5E /* Frameworks */ = { + isa = PBXFrameworksBuildPhase; + buildActionMask = 2147483647; + files = ( + ); + runOnlyForDeploymentPostprocessing = 0; + }; +/* End PBXFrameworksBuildPhase section */ + +/* Begin PBXGroup section */ + 08FB7794FE84155DC02AAC07 /* udptest */ = { + isa = PBXGroup; + children = ( + 08FB7795FE84155DC02AAC07 /* Source */, + C6A0FF2B0290797F04C91782 /* Documentation */, + 1AB674ADFE9D54B511CA2CBB /* Products */, + ); + name = udptest; + sourceTree = ""; + }; + 08FB7795FE84155DC02AAC07 /* Source */ = { + isa = PBXGroup; + children = ( + 08FB7796FE84155DC02AAC07 /* main.c */, + ); + name = Source; + sourceTree = ""; + }; + 1AB674ADFE9D54B511CA2CBB /* Products */ = { + isa = PBXGroup; + children = ( + 8DD76FB20486AB0100D96B5E /* udptest */, + ); + name = Products; + sourceTree = ""; + }; + C6A0FF2B0290797F04C91782 /* Documentation */ = { + isa = PBXGroup; + children = ( + C6A0FF2C0290799A04C91782 /* udptest.1 */, + ); + name = Documentation; + sourceTree = ""; + }; +/* End PBXGroup section */ + +/* Begin PBXNativeTarget section */ + 8DD76FA90486AB0100D96B5E /* udptest */ = { + isa = PBXNativeTarget; + buildConfigurationList = 1DEB928508733DD80010E9CD /* Build configuration list for PBXNativeTarget "udptest" */; + buildPhases = ( + 8DD76FAB0486AB0100D96B5E /* Sources */, + 8DD76FAD0486AB0100D96B5E /* Frameworks */, + 8DD76FAF0486AB0100D96B5E /* CopyFiles */, + ); + buildRules = ( + ); + dependencies = ( + ); + name = udptest; + productInstallPath = "$(HOME)/bin"; + productName = udptest; + productReference = 8DD76FB20486AB0100D96B5E /* udptest */; + productType = "com.apple.product-type.tool"; + }; +/* End PBXNativeTarget section */ + +/* Begin PBXProject section */ + 08FB7793FE84155DC02AAC07 /* Project object */ = { + isa = PBXProject; + buildConfigurationList = 1DEB928908733DD80010E9CD /* Build configuration list for PBXProject "udptest" */; + compatibilityVersion = "Xcode 3.1"; + developmentRegion = English; + hasScannedForEncodings = 1; + knownRegions = ( + English, + Japanese, + French, + German, + ); + mainGroup = 08FB7794FE84155DC02AAC07 /* udptest */; + projectDirPath = ""; + projectRoot = ""; + targets = ( + 8DD76FA90486AB0100D96B5E /* udptest */, + ); + }; +/* End PBXProject section */ + +/* Begin PBXSourcesBuildPhase section */ + 8DD76FAB0486AB0100D96B5E /* Sources */ = { + isa = PBXSourcesBuildPhase; + buildActionMask = 2147483647; + files = ( + 8DD76FAC0486AB0100D96B5E /* main.c in Sources */, + ); + runOnlyForDeploymentPostprocessing = 0; + }; +/* End PBXSourcesBuildPhase section */ + +/* Begin XCBuildConfiguration section */ + 1DEB928608733DD80010E9CD /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + ALWAYS_SEARCH_USER_PATHS = NO; + COPY_PHASE_STRIP = NO; + GCC_DYNAMIC_NO_PIC = NO; + GCC_ENABLE_FIX_AND_CONTINUE = YES; + GCC_MODEL_TUNING = G5; + GCC_OPTIMIZATION_LEVEL = 0; + INSTALL_PATH = /usr/local/bin; + PRODUCT_NAME = udptest; + }; + name = Debug; + }; + 1DEB928708733DD80010E9CD /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + ALWAYS_SEARCH_USER_PATHS = NO; + DEBUG_INFORMATION_FORMAT = "dwarf-with-dsym"; + GCC_MODEL_TUNING = G5; + INSTALL_PATH = /usr/local/bin; + PRODUCT_NAME = udptest; + }; + name = Release; + }; + 1DEB928A08733DD80010E9CD /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + ARCHS = "$(ARCHS_STANDARD_32_64_BIT)"; + GCC_C_LANGUAGE_STANDARD = gnu99; + GCC_OPTIMIZATION_LEVEL = 0; + GCC_WARN_ABOUT_RETURN_TYPE = YES; + GCC_WARN_UNUSED_VARIABLE = YES; + HEADER_SEARCH_PATHS = ../../include/common/; + ONLY_ACTIVE_ARCH = YES; + PREBINDING = NO; + SDKROOT = macosx10.6; + }; + name = Debug; + }; + 1DEB928B08733DD80010E9CD /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + ARCHS = "$(ARCHS_STANDARD_32_64_BIT)"; + GCC_C_LANGUAGE_STANDARD = gnu99; + GCC_WARN_ABOUT_RETURN_TYPE = YES; + GCC_WARN_UNUSED_VARIABLE = YES; + PREBINDING = NO; + SDKROOT = macosx10.6; + }; + name = Release; + }; +/* End XCBuildConfiguration section */ + +/* Begin XCConfigurationList section */ + 1DEB928508733DD80010E9CD /* Build configuration list for PBXNativeTarget "udptest" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + 1DEB928608733DD80010E9CD /* Debug */, + 1DEB928708733DD80010E9CD /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; + 1DEB928908733DD80010E9CD /* Build configuration list for PBXProject "udptest" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + 1DEB928A08733DD80010E9CD /* Debug */, + 1DEB928B08733DD80010E9CD /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; +/* End XCConfigurationList section */ + }; + rootObject = 08FB7793FE84155DC02AAC07 /* Project object */; +} diff --git a/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.mode1v3 b/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.mode1v3 new file mode 100644 index 0000000000..2bf1029cec --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.mode1v3 @@ -0,0 +1,1440 @@ + + + + + ActivePerspectiveName + Project + AllowedModules + + + BundleLoadPath + + MaxInstances + n + Module + PBXSmartGroupTreeModule + Name + Groups and Files Outline View + + + BundleLoadPath + + MaxInstances + n + Module + PBXNavigatorGroup + Name + Editor + + + BundleLoadPath + + MaxInstances + n + Module + XCTaskListModule + Name + Task List + + + BundleLoadPath + + MaxInstances + n + Module + XCDetailModule + Name + File and Smart Group Detail Viewer + + + BundleLoadPath + + MaxInstances + 1 + Module + PBXBuildResultsModule + Name + Detailed Build Results Viewer + + + BundleLoadPath + + MaxInstances + 1 + Module + PBXProjectFindModule + Name + Project Batch Find Tool + + + BundleLoadPath + + MaxInstances + n + Module + XCProjectFormatConflictsModule + Name + Project Format Conflicts List + + + BundleLoadPath + + MaxInstances + n + Module + PBXBookmarksModule + Name + Bookmarks Tool + + + BundleLoadPath + + MaxInstances + n + Module + PBXClassBrowserModule + Name + Class Browser + + + BundleLoadPath + + MaxInstances + n + Module + PBXCVSModule + Name + Source Code Control Tool + + + BundleLoadPath + + MaxInstances + n + Module + PBXDebugBreakpointsModule + Name + Debug Breakpoints Tool + + + BundleLoadPath + + MaxInstances + n + Module + XCDockableInspector + Name + Inspector + + + BundleLoadPath + + MaxInstances + n + Module + PBXOpenQuicklyModule + Name + Open Quickly Tool + + + BundleLoadPath + + MaxInstances + 1 + Module + PBXDebugSessionModule + Name + Debugger + + + BundleLoadPath + + MaxInstances + 1 + Module + PBXDebugCLIModule + Name + Debug Console + + + BundleLoadPath + + MaxInstances + n + Module + XCSnapshotModule + Name + Snapshots Tool + + + BundlePath + /Developer/Library/PrivateFrameworks/DevToolsInterface.framework/Resources + Description + DefaultDescriptionKey + DockingSystemVisible + + Extension + mode1v3 + FavBarConfig + + PBXProjectModuleGUID + CEA4FF3213E6BD8E002506EF + XCBarModuleItemNames + + XCBarModuleItems + + + FirstTimeWindowDisplayed + + Identifier + com.apple.perspectives.project.mode1v3 + MajorVersion + 33 + MinorVersion + 0 + Name + Default + Notifications + + OpenEditors + + + Content + + PBXProjectModuleGUID + CED081F713E6F90000BAE9DD + PBXProjectModuleLabel + px_waypointplanner.cc + PBXSplitModuleInNavigatorKey + + Split0 + + PBXProjectModuleGUID + CED081F813E6F90000BAE9DD + PBXProjectModuleLabel + px_waypointplanner.cc + _historyCapacity + 0 + bookmark + CED081FB13E6F90000BAE9DD + history + + CED081F913E6F90000BAE9DD + + + SplitCount + 1 + + StatusBarVisibility + + + Geometry + + Frame + {{0, 20}, {995, 634}} + PBXModuleWindowStatusBarHidden2 + + RubberWindowFrame + 15 103 995 675 0 0 1280 778 + + + + PerspectiveWidths + + -1 + -1 + + Perspectives + + + ChosenToolbarItems + + active-combo-popup + action + NSToolbarFlexibleSpaceItem + debugger-enable-breakpoints + build-and-go + com.apple.ide.PBXToolbarStopButton + get-info + NSToolbarFlexibleSpaceItem + com.apple.pbx.toolbar.searchfield + + ControllerClassBaseName + + IconName + WindowOfProjectWithEditor + Identifier + perspective.project + IsVertical + + Layout + + + ContentConfiguration + + PBXBottomSmartGroupGIDs + + 1C37FBAC04509CD000000102 + 1C37FAAC04509CD000000102 + 1C37FABC05509CD000000102 + 1C37FABC05539CD112110102 + E2644B35053B69B200211256 + 1C37FABC04509CD000100104 + 1CC0EA4004350EF90044410B + 1CC0EA4004350EF90041110B + + PBXProjectModuleGUID + 1CE0B1FE06471DED0097A5F4 + PBXProjectModuleLabel + Files + PBXProjectStructureProvided + yes + PBXSmartGroupTreeModuleColumnData + + PBXSmartGroupTreeModuleColumnWidthsKey + + 186 + + PBXSmartGroupTreeModuleColumnsKey_v4 + + MainColumn + + + PBXSmartGroupTreeModuleOutlineStateKey_v7 + + PBXSmartGroupTreeModuleOutlineStateExpansionKey + + 08FB7794FE84155DC02AAC07 + 1C37FBAC04509CD000000102 + 1C37FABC05509CD000000102 + + PBXSmartGroupTreeModuleOutlineStateSelectionKey + + + 0 + + + PBXSmartGroupTreeModuleOutlineStateVisibleRectKey + {{0, 0}, {186, 615}} + + PBXTopSmartGroupGIDs + + XCIncludePerspectivesSwitch + + XCSharingToken + com.apple.Xcode.GFSharingToken + + GeometryConfiguration + + Frame + {{0, 0}, {203, 633}} + GroupTreeTableConfiguration + + MainColumn + 186 + + RubberWindowFrame + 0 104 1280 674 0 0 1280 778 + + Module + PBXSmartGroupTreeModule + Proportion + 203pt + + + Dock + + + ContentConfiguration + + PBXProjectModuleGUID + 1CE0B20306471E060097A5F4 + PBXProjectModuleLabel + mavlink_msg_waypoint_count.h + PBXSplitModuleInNavigatorKey + + Split0 + + PBXProjectModuleGUID + 1CE0B20406471E060097A5F4 + PBXProjectModuleLabel + mavlink_msg_waypoint_count.h + _historyCapacity + 0 + bookmark + CED081F313E6F90000BAE9DD + history + + CED081EC13E6F90000BAE9DD + CED081ED13E6F90000BAE9DD + CED081EF13E6F90000BAE9DD + CED081F113E6F90000BAE9DD + + + SplitCount + 1 + + StatusBarVisibility + + + GeometryConfiguration + + Frame + {{0, 0}, {1072, 556}} + RubberWindowFrame + 0 104 1280 674 0 0 1280 778 + + Module + PBXNavigatorGroup + Proportion + 556pt + + + BecomeActive + + ContentConfiguration + + PBXProjectModuleGUID + 1CE0B20506471E060097A5F4 + PBXProjectModuleLabel + Detail + + GeometryConfiguration + + Frame + {{0, 561}, {1072, 72}} + RubberWindowFrame + 0 104 1280 674 0 0 1280 778 + + Module + XCDetailModule + Proportion + 72pt + + + Proportion + 1072pt + + + Name + Project + ServiceClasses + + XCModuleDock + PBXSmartGroupTreeModule + XCModuleDock + PBXNavigatorGroup + XCDetailModule + + TableOfContents + + CED081F513E6F90000BAE9DD + 1CE0B1FE06471DED0097A5F4 + CED081F613E6F90000BAE9DD + 1CE0B20306471E060097A5F4 + 1CE0B20506471E060097A5F4 + + ToolbarConfigUserDefaultsMinorVersion + 2 + ToolbarConfiguration + xcode.toolbar.config.defaultV3 + + + ControllerClassBaseName + + IconName + WindowOfProject + Identifier + perspective.morph + IsVertical + 0 + Layout + + + BecomeActive + 1 + ContentConfiguration + + PBXBottomSmartGroupGIDs + + 1C37FBAC04509CD000000102 + 1C37FAAC04509CD000000102 + 1C08E77C0454961000C914BD + 1C37FABC05509CD000000102 + 1C37FABC05539CD112110102 + E2644B35053B69B200211256 + 1C37FABC04509CD000100104 + 1CC0EA4004350EF90044410B + 1CC0EA4004350EF90041110B + + PBXProjectModuleGUID + 11E0B1FE06471DED0097A5F4 + PBXProjectModuleLabel + Files + PBXProjectStructureProvided + yes + PBXSmartGroupTreeModuleColumnData + + PBXSmartGroupTreeModuleColumnWidthsKey + + 186 + + PBXSmartGroupTreeModuleColumnsKey_v4 + + MainColumn + + + PBXSmartGroupTreeModuleOutlineStateKey_v7 + + PBXSmartGroupTreeModuleOutlineStateExpansionKey + + 29B97314FDCFA39411CA2CEA + 1C37FABC05509CD000000102 + + PBXSmartGroupTreeModuleOutlineStateSelectionKey + + + 0 + + + PBXSmartGroupTreeModuleOutlineStateVisibleRectKey + {{0, 0}, {186, 337}} + + PBXTopSmartGroupGIDs + + XCIncludePerspectivesSwitch + 1 + XCSharingToken + com.apple.Xcode.GFSharingToken + + GeometryConfiguration + + Frame + {{0, 0}, {203, 355}} + GroupTreeTableConfiguration + + MainColumn + 186 + + RubberWindowFrame + 373 269 690 397 0 0 1440 878 + + Module + PBXSmartGroupTreeModule + Proportion + 100% + + + Name + Morph + PreferredWidth + 300 + ServiceClasses + + XCModuleDock + PBXSmartGroupTreeModule + + TableOfContents + + 11E0B1FE06471DED0097A5F4 + + ToolbarConfiguration + xcode.toolbar.config.default.shortV3 + + + PerspectivesBarVisible + + ShelfIsVisible + + SourceDescription + file at '/Developer/Library/PrivateFrameworks/DevToolsInterface.framework/Resources/XCPerspectivesSpecificationMode1.xcperspec' + StatusbarIsVisible + + TimeStamp + 0.0 + ToolbarConfigUserDefaultsMinorVersion + 2 + ToolbarDisplayMode + 1 + ToolbarIsVisible + + ToolbarSizeMode + 1 + Type + Perspectives + UpdateMessage + The Default Workspace in this version of Xcode now includes support to hide and show the detail view (what has been referred to as the "Metro-Morph" feature). You must discard your current Default Workspace settings and update to the latest Default Workspace in order to gain this feature. Do you wish to update to the latest Workspace defaults for project '%@'? + WindowJustification + 5 + WindowOrderList + + CED0820513E6F90000BAE9DD + CED0820613E6F90000BAE9DD + CED0820713E6F90000BAE9DD + 1C78EAAD065D492600B07095 + 1CD10A99069EF8BA00B06720 + CEA4FF3313E6BD8E002506EF + CED081F713E6F90000BAE9DD + /Users/user/src/mavlink10/missionlib/testing/udptest.xcodeproj + + WindowString + 0 104 1280 674 0 0 1280 778 + WindowToolsV3 + + + FirstTimeWindowDisplayed + + Identifier + windowTool.build + IsVertical + + Layout + + + Dock + + + ContentConfiguration + + PBXProjectModuleGUID + 1CD0528F0623707200166675 + PBXProjectModuleLabel + + StatusBarVisibility + + + GeometryConfiguration + + Frame + {{0, 0}, {500, 218}} + RubberWindowFrame + 29 258 500 500 0 0 1280 778 + + Module + PBXNavigatorGroup + Proportion + 218pt + + + ContentConfiguration + + PBXProjectModuleGUID + XCMainBuildResultsModuleGUID + PBXProjectModuleLabel + Build Results + XCBuildResultsTrigger_Collapse + 1021 + XCBuildResultsTrigger_Open + 1011 + + GeometryConfiguration + + Frame + {{0, 223}, {500, 236}} + RubberWindowFrame + 29 258 500 500 0 0 1280 778 + + Module + PBXBuildResultsModule + Proportion + 236pt + + + Proportion + 459pt + + + Name + Build Results + ServiceClasses + + PBXBuildResultsModule + + StatusbarIsVisible + + TableOfContents + + CEA4FF3313E6BD8E002506EF + CED081FD13E6F90000BAE9DD + 1CD0528F0623707200166675 + XCMainBuildResultsModuleGUID + + ToolbarConfiguration + xcode.toolbar.config.buildV3 + WindowContentMinSize + 486 300 + WindowString + 29 258 500 500 0 0 1280 778 + WindowToolGUID + CEA4FF3313E6BD8E002506EF + WindowToolIsVisible + + + + FirstTimeWindowDisplayed + + Identifier + windowTool.debugger + IsVertical + + Layout + + + Dock + + + ContentConfiguration + + Debugger + + HorizontalSplitView + + _collapsingFrameDimension + 0.0 + _indexOfCollapsedView + 0 + _percentageOfCollapsedView + 0.0 + isCollapsed + yes + sizes + + {{0, 0}, {316, 198}} + {{316, 0}, {378, 198}} + + + VerticalSplitView + + _collapsingFrameDimension + 0.0 + _indexOfCollapsedView + 0 + _percentageOfCollapsedView + 0.0 + isCollapsed + yes + sizes + + {{0, 0}, {694, 198}} + {{0, 198}, {694, 183}} + + + + LauncherConfigVersion + 8 + PBXProjectModuleGUID + 1C162984064C10D400B95A72 + PBXProjectModuleLabel + Debug - GLUTExamples (Underwater) + + GeometryConfiguration + + DebugConsoleVisible + None + DebugConsoleWindowFrame + {{200, 200}, {500, 300}} + DebugSTDIOWindowFrame + {{200, 200}, {500, 300}} + Frame + {{0, 0}, {694, 381}} + PBXDebugSessionStackFrameViewKey + + DebugVariablesTableConfiguration + + Name + 120 + Value + 85 + Summary + 148 + + Frame + {{316, 0}, {378, 198}} + RubberWindowFrame + 196 241 694 422 0 0 1280 778 + + RubberWindowFrame + 196 241 694 422 0 0 1280 778 + + Module + PBXDebugSessionModule + Proportion + 381pt + + + Proportion + 381pt + + + Name + Debugger + ServiceClasses + + PBXDebugSessionModule + + StatusbarIsVisible + + TableOfContents + + 1CD10A99069EF8BA00B06720 + CED081FE13E6F90000BAE9DD + 1C162984064C10D400B95A72 + CED081FF13E6F90000BAE9DD + CED0820013E6F90000BAE9DD + CED0820113E6F90000BAE9DD + CED0820213E6F90000BAE9DD + CED0820313E6F90000BAE9DD + + ToolbarConfiguration + xcode.toolbar.config.debugV3 + WindowString + 196 241 694 422 0 0 1280 778 + WindowToolGUID + 1CD10A99069EF8BA00B06720 + WindowToolIsVisible + + + + Identifier + windowTool.find + Layout + + + Dock + + + Dock + + + ContentConfiguration + + PBXProjectModuleGUID + 1CDD528C0622207200134675 + PBXProjectModuleLabel + <No Editor> + PBXSplitModuleInNavigatorKey + + Split0 + + PBXProjectModuleGUID + 1CD0528D0623707200166675 + + SplitCount + 1 + + StatusBarVisibility + 1 + + GeometryConfiguration + + Frame + {{0, 0}, {781, 167}} + RubberWindowFrame + 62 385 781 470 0 0 1440 878 + + Module + PBXNavigatorGroup + Proportion + 781pt + + + Proportion + 50% + + + BecomeActive + 1 + ContentConfiguration + + PBXProjectModuleGUID + 1CD0528E0623707200166675 + PBXProjectModuleLabel + Project Find + + GeometryConfiguration + + Frame + {{8, 0}, {773, 254}} + RubberWindowFrame + 62 385 781 470 0 0 1440 878 + + Module + PBXProjectFindModule + Proportion + 50% + + + Proportion + 428pt + + + Name + Project Find + ServiceClasses + + PBXProjectFindModule + + StatusbarIsVisible + 1 + TableOfContents + + 1C530D57069F1CE1000CFCEE + 1C530D58069F1CE1000CFCEE + 1C530D59069F1CE1000CFCEE + 1CDD528C0622207200134675 + 1C530D5A069F1CE1000CFCEE + 1CE0B1FE06471DED0097A5F4 + 1CD0528E0623707200166675 + + WindowString + 62 385 781 470 0 0 1440 878 + WindowToolGUID + 1C530D57069F1CE1000CFCEE + WindowToolIsVisible + 0 + + + Identifier + MENUSEPARATOR + + + FirstTimeWindowDisplayed + + Identifier + windowTool.debuggerConsole + IsVertical + + Layout + + + Dock + + + ContentConfiguration + + PBXProjectModuleGUID + 1C78EAAC065D492600B07095 + PBXProjectModuleLabel + Debugger Console + + GeometryConfiguration + + Frame + {{0, 0}, {650, 209}} + RubberWindowFrame + 205 385 650 250 0 0 1280 778 + + Module + PBXDebugCLIModule + Proportion + 209pt + + + Proportion + 209pt + + + Name + Debugger Console + ServiceClasses + + PBXDebugCLIModule + + StatusbarIsVisible + + TableOfContents + + 1C78EAAD065D492600B07095 + CED0820413E6F90000BAE9DD + 1C78EAAC065D492600B07095 + + ToolbarConfiguration + xcode.toolbar.config.consoleV3 + WindowString + 205 385 650 250 0 0 1280 778 + WindowToolGUID + 1C78EAAD065D492600B07095 + WindowToolIsVisible + + + + Identifier + windowTool.snapshots + Layout + + + Dock + + + Module + XCSnapshotModule + Proportion + 100% + + + Proportion + 100% + + + Name + Snapshots + ServiceClasses + + XCSnapshotModule + + StatusbarIsVisible + Yes + ToolbarConfiguration + xcode.toolbar.config.snapshots + WindowString + 315 824 300 550 0 0 1440 878 + WindowToolIsVisible + Yes + + + Identifier + windowTool.scm + Layout + + + Dock + + + ContentConfiguration + + PBXProjectModuleGUID + 1C78EAB2065D492600B07095 + PBXProjectModuleLabel + <No Editor> + PBXSplitModuleInNavigatorKey + + Split0 + + PBXProjectModuleGUID + 1C78EAB3065D492600B07095 + + SplitCount + 1 + + StatusBarVisibility + 1 + + GeometryConfiguration + + Frame + {{0, 0}, {452, 0}} + RubberWindowFrame + 743 379 452 308 0 0 1280 1002 + + Module + PBXNavigatorGroup + Proportion + 0pt + + + BecomeActive + 1 + ContentConfiguration + + PBXProjectModuleGUID + 1CD052920623707200166675 + PBXProjectModuleLabel + SCM + + GeometryConfiguration + + ConsoleFrame + {{0, 259}, {452, 0}} + Frame + {{0, 7}, {452, 259}} + RubberWindowFrame + 743 379 452 308 0 0 1280 1002 + TableConfiguration + + Status + 30 + FileName + 199 + Path + 197.0950012207031 + + TableFrame + {{0, 0}, {452, 250}} + + Module + PBXCVSModule + Proportion + 262pt + + + Proportion + 266pt + + + Name + SCM + ServiceClasses + + PBXCVSModule + + StatusbarIsVisible + 1 + TableOfContents + + 1C78EAB4065D492600B07095 + 1C78EAB5065D492600B07095 + 1C78EAB2065D492600B07095 + 1CD052920623707200166675 + + ToolbarConfiguration + xcode.toolbar.config.scm + WindowString + 743 379 452 308 0 0 1280 1002 + + + Identifier + windowTool.breakpoints + IsVertical + 0 + Layout + + + Dock + + + BecomeActive + 1 + ContentConfiguration + + PBXBottomSmartGroupGIDs + + 1C77FABC04509CD000000102 + + PBXProjectModuleGUID + 1CE0B1FE06471DED0097A5F4 + PBXProjectModuleLabel + Files + PBXProjectStructureProvided + no + PBXSmartGroupTreeModuleColumnData + + PBXSmartGroupTreeModuleColumnWidthsKey + + 168 + + PBXSmartGroupTreeModuleColumnsKey_v4 + + MainColumn + + + PBXSmartGroupTreeModuleOutlineStateKey_v7 + + PBXSmartGroupTreeModuleOutlineStateExpansionKey + + 1C77FABC04509CD000000102 + + PBXSmartGroupTreeModuleOutlineStateSelectionKey + + + 0 + + + PBXSmartGroupTreeModuleOutlineStateVisibleRectKey + {{0, 0}, {168, 350}} + + PBXTopSmartGroupGIDs + + XCIncludePerspectivesSwitch + 0 + + GeometryConfiguration + + Frame + {{0, 0}, {185, 368}} + GroupTreeTableConfiguration + + MainColumn + 168 + + RubberWindowFrame + 315 424 744 409 0 0 1440 878 + + Module + PBXSmartGroupTreeModule + Proportion + 185pt + + + ContentConfiguration + + PBXProjectModuleGUID + 1CA1AED706398EBD00589147 + PBXProjectModuleLabel + Detail + + GeometryConfiguration + + Frame + {{190, 0}, {554, 368}} + RubberWindowFrame + 315 424 744 409 0 0 1440 878 + + Module + XCDetailModule + Proportion + 554pt + + + Proportion + 368pt + + + MajorVersion + 3 + MinorVersion + 0 + Name + Breakpoints + ServiceClasses + + PBXSmartGroupTreeModule + XCDetailModule + + StatusbarIsVisible + 1 + TableOfContents + + 1CDDB66807F98D9800BB5817 + 1CDDB66907F98D9800BB5817 + 1CE0B1FE06471DED0097A5F4 + 1CA1AED706398EBD00589147 + + ToolbarConfiguration + xcode.toolbar.config.breakpointsV3 + WindowString + 315 424 744 409 0 0 1440 878 + WindowToolGUID + 1CDDB66807F98D9800BB5817 + WindowToolIsVisible + 1 + + + Identifier + windowTool.debugAnimator + Layout + + + Dock + + + Module + PBXNavigatorGroup + Proportion + 100% + + + Proportion + 100% + + + Name + Debug Visualizer + ServiceClasses + + PBXNavigatorGroup + + StatusbarIsVisible + 1 + ToolbarConfiguration + xcode.toolbar.config.debugAnimatorV3 + WindowString + 100 100 700 500 0 0 1280 1002 + + + Identifier + windowTool.bookmarks + Layout + + + Dock + + + Module + PBXBookmarksModule + Proportion + 100% + + + Proportion + 100% + + + Name + Bookmarks + ServiceClasses + + PBXBookmarksModule + + StatusbarIsVisible + 0 + WindowString + 538 42 401 187 0 0 1280 1002 + + + Identifier + windowTool.projectFormatConflicts + Layout + + + Dock + + + Module + XCProjectFormatConflictsModule + Proportion + 100% + + + Proportion + 100% + + + Name + Project Format Conflicts + ServiceClasses + + XCProjectFormatConflictsModule + + StatusbarIsVisible + 0 + WindowContentMinSize + 450 300 + WindowString + 50 850 472 307 0 0 1440 877 + + + Identifier + windowTool.classBrowser + Layout + + + Dock + + + BecomeActive + 1 + ContentConfiguration + + OptionsSetName + Hierarchy, all classes + PBXProjectModuleGUID + 1CA6456E063B45B4001379D8 + PBXProjectModuleLabel + Class Browser - NSObject + + GeometryConfiguration + + ClassesFrame + {{0, 0}, {374, 96}} + ClassesTreeTableConfiguration + + PBXClassNameColumnIdentifier + 208 + PBXClassBookColumnIdentifier + 22 + + Frame + {{0, 0}, {630, 331}} + MembersFrame + {{0, 105}, {374, 395}} + MembersTreeTableConfiguration + + PBXMemberTypeIconColumnIdentifier + 22 + PBXMemberNameColumnIdentifier + 216 + PBXMemberTypeColumnIdentifier + 97 + PBXMemberBookColumnIdentifier + 22 + + PBXModuleWindowStatusBarHidden2 + 1 + RubberWindowFrame + 385 179 630 352 0 0 1440 878 + + Module + PBXClassBrowserModule + Proportion + 332pt + + + Proportion + 332pt + + + Name + Class Browser + ServiceClasses + + PBXClassBrowserModule + + StatusbarIsVisible + 0 + TableOfContents + + 1C0AD2AF069F1E9B00FABCE6 + 1C0AD2B0069F1E9B00FABCE6 + 1CA6456E063B45B4001379D8 + + ToolbarConfiguration + xcode.toolbar.config.classbrowser + WindowString + 385 179 630 352 0 0 1440 878 + WindowToolGUID + 1C0AD2AF069F1E9B00FABCE6 + WindowToolIsVisible + 0 + + + Identifier + windowTool.refactoring + IncludeInToolsMenu + 0 + Layout + + + Dock + + + BecomeActive + 1 + GeometryConfiguration + + Frame + {0, 0}, {500, 335} + RubberWindowFrame + {0, 0}, {500, 335} + + Module + XCRefactoringModule + Proportion + 100% + + + Proportion + 100% + + + Name + Refactoring + ServiceClasses + + XCRefactoringModule + + WindowString + 200 200 500 356 0 0 1920 1200 + + + + diff --git a/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.pbxuser b/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.pbxuser new file mode 100644 index 0000000000..548d2fa89d --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/testing/udptest.xcodeproj/user.pbxuser @@ -0,0 +1,236 @@ +// !$*UTF8*$! +{ + 08FB7793FE84155DC02AAC07 /* Project object */ = { + activeBuildConfigurationName = Debug; + activeExecutable = CEA4FF2913E6BD6D002506EF /* udptest */; + activeTarget = 8DD76FA90486AB0100D96B5E /* udptest */; + codeSenseManager = CEA4FF4013E6BD8E002506EF /* Code sense */; + executables = ( + CEA4FF2913E6BD6D002506EF /* udptest */, + ); + perUserDictionary = { + PBXConfiguration.PBXFileTableDataSource3.PBXFileTableDataSource = { + PBXFileTableDataSourceColumnSortingDirectionKey = "-1"; + PBXFileTableDataSourceColumnSortingKey = PBXFileDataSource_Filename_ColumnID; + PBXFileTableDataSourceColumnWidthsKey = ( + 20, + 833, + 20, + 48, + 43, + 43, + 20, + ); + PBXFileTableDataSourceColumnsKey = ( + PBXFileDataSource_FiletypeID, + PBXFileDataSource_Filename_ColumnID, + PBXFileDataSource_Built_ColumnID, + PBXFileDataSource_ObjectSize_ColumnID, + PBXFileDataSource_Errors_ColumnID, + PBXFileDataSource_Warnings_ColumnID, + PBXFileDataSource_Target_ColumnID, + ); + }; + PBXConfiguration.PBXTargetDataSource.PBXTargetDataSource = { + PBXFileTableDataSourceColumnSortingDirectionKey = "-1"; + PBXFileTableDataSourceColumnSortingKey = PBXFileDataSource_Filename_ColumnID; + PBXFileTableDataSourceColumnWidthsKey = ( + 20, + 301, + 60, + 20, + 48, + 43, + 43, + ); + PBXFileTableDataSourceColumnsKey = ( + PBXFileDataSource_FiletypeID, + PBXFileDataSource_Filename_ColumnID, + PBXTargetDataSource_PrimaryAttribute, + PBXFileDataSource_Built_ColumnID, + PBXFileDataSource_ObjectSize_ColumnID, + PBXFileDataSource_Errors_ColumnID, + PBXFileDataSource_Warnings_ColumnID, + ); + }; + PBXPerProjectTemplateStateSaveDate = 333907732; + PBXWorkspaceStateSaveDate = 333907732; + }; + perUserProjectItems = { + CED081EC13E6F90000BAE9DD = CED081EC13E6F90000BAE9DD /* PBXTextBookmark */; + CED081ED13E6F90000BAE9DD = CED081ED13E6F90000BAE9DD /* PBXTextBookmark */; + CED081EF13E6F90000BAE9DD = CED081EF13E6F90000BAE9DD /* PBXTextBookmark */; + CED081F113E6F90000BAE9DD = CED081F113E6F90000BAE9DD /* PBXTextBookmark */; + CED081F313E6F90000BAE9DD = CED081F313E6F90000BAE9DD /* PBXTextBookmark */; + CED081F913E6F90000BAE9DD = CED081F913E6F90000BAE9DD /* PBXTextBookmark */; + CED081FB13E6F90000BAE9DD = CED081FB13E6F90000BAE9DD /* PBXTextBookmark */; + }; + sourceControlManager = CEA4FF3F13E6BD8E002506EF /* Source Control */; + userBuildSettings = { + }; + }; + 08FB7796FE84155DC02AAC07 /* main.c */ = { + uiCtxt = { + sepNavIntBoundsRect = "{{0, 0}, {1797, 14781}}"; + sepNavSelRange = "{32946, 0}"; + sepNavVisRange = "{32608, 2708}"; + sepNavWindowFrame = "{{374, 47}, {906, 731}}"; + }; + }; + 8DD76FA90486AB0100D96B5E /* udptest */ = { + activeExec = 0; + executables = ( + CEA4FF2913E6BD6D002506EF /* udptest */, + ); + }; + CEA4FF2913E6BD6D002506EF /* udptest */ = { + isa = PBXExecutable; + activeArgIndices = ( + ); + argumentStrings = ( + ); + autoAttachOnCrash = 1; + breakpointsEnabled = 0; + configStateDict = { + }; + customDataFormattersEnabled = 1; + dataTipCustomDataFormattersEnabled = 1; + dataTipShowTypeColumn = 1; + dataTipSortType = 0; + debuggerPlugin = GDBDebugging; + disassemblyDisplayState = 0; + dylibVariantSuffix = ""; + enableDebugStr = 1; + environmentEntries = ( + ); + executableSystemSymbolLevel = 0; + executableUserSymbolLevel = 0; + libgmallocEnabled = 0; + name = udptest; + savedGlobals = { + }; + showTypeColumn = 0; + sourceDirectories = ( + ); + }; + CEA4FF3F13E6BD8E002506EF /* Source Control */ = { + isa = PBXSourceControlManager; + fallbackIsa = XCSourceControlManager; + isSCMEnabled = 0; + scmConfiguration = { + repositoryNamesForRoots = { + "" = ""; + }; + }; + }; + CEA4FF4013E6BD8E002506EF /* Code sense */ = { + isa = PBXCodeSenseManager; + indexTemplatePath = ""; + }; + CED081EC13E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = 08FB7796FE84155DC02AAC07 /* main.c */; + name = "main.c: 678"; + rLen = 31; + rLoc = 25201; + rType = 0; + vrLen = 2936; + vrLoc = 23777; + }; + CED081ED13E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = CED081EE13E6F90000BAE9DD /* mavlink_msg_waypoint_request.h */; + name = "mavlink_msg_waypoint_request.h: 1"; + rLen = 0; + rLoc = 0; + rType = 0; + vrLen = 1362; + vrLoc = 0; + }; + CED081EE13E6F90000BAE9DD /* mavlink_msg_waypoint_request.h */ = { + isa = PBXFileReference; + lastKnownFileType = sourcecode.c.h; + name = mavlink_msg_waypoint_request.h; + path = /Users/user/src/mavlink10/include/common/mavlink_msg_waypoint_request.h; + sourceTree = ""; + }; + CED081EF13E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = CED081F013E6F90000BAE9DD /* mavlink_msg_waypoint_clear_all.h */; + name = "mavlink_msg_waypoint_clear_all.h: 1"; + rLen = 0; + rLoc = 0; + rType = 0; + vrLen = 1447; + vrLoc = 0; + }; + CED081F013E6F90000BAE9DD /* mavlink_msg_waypoint_clear_all.h */ = { + isa = PBXFileReference; + lastKnownFileType = sourcecode.c.h; + name = mavlink_msg_waypoint_clear_all.h; + path = /Users/user/src/mavlink10/include/common/mavlink_msg_waypoint_clear_all.h; + sourceTree = ""; + }; + CED081F113E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = CED081F213E6F90000BAE9DD /* mavlink_msg_waypoint_count.h */; + rLen = 0; + rLoc = 9223372036854775808; + rType = 0; + }; + CED081F213E6F90000BAE9DD /* mavlink_msg_waypoint_count.h */ = { + isa = PBXFileReference; + lastKnownFileType = sourcecode.c.h; + name = mavlink_msg_waypoint_count.h; + path = /Users/user/src/mavlink10/include/common/mavlink_msg_waypoint_count.h; + sourceTree = ""; + }; + CED081F313E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = CED081F413E6F90000BAE9DD /* mavlink_msg_waypoint_count.h */; + name = "mavlink_msg_waypoint_count.h: 1"; + rLen = 0; + rLoc = 0; + rType = 0; + vrLen = 1530; + vrLoc = 0; + }; + CED081F413E6F90000BAE9DD /* mavlink_msg_waypoint_count.h */ = { + isa = PBXFileReference; + lastKnownFileType = sourcecode.c.h; + name = mavlink_msg_waypoint_count.h; + path = /Users/user/src/mavlink10/include/common/mavlink_msg_waypoint_count.h; + sourceTree = ""; + }; + CED081F913E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = CED081FA13E6F90000BAE9DD /* px_waypointplanner.cc */; + rLen = 0; + rLoc = 41642; + rType = 0; + }; + CED081FA13E6F90000BAE9DD /* px_waypointplanner.cc */ = { + isa = PBXFileReference; + lastKnownFileType = sourcecode.cpp.cpp; + name = px_waypointplanner.cc; + path = /Users/user/Documents/pixhawk/mavconn/src/planning/px_waypointplanner.cc; + sourceTree = ""; + }; + CED081FB13E6F90000BAE9DD /* PBXTextBookmark */ = { + isa = PBXTextBookmark; + fRef = CED081FC13E6F90000BAE9DD /* px_waypointplanner.cc */; + name = "px_waypointplanner.cc: 30"; + rLen = 561; + rLoc = 785; + rType = 0; + vrLen = 1834; + vrLoc = 33761; + }; + CED081FC13E6F90000BAE9DD /* px_waypointplanner.cc */ = { + isa = PBXFileReference; + lastKnownFileType = sourcecode.cpp.cpp; + name = px_waypointplanner.cc; + path = /Users/user/Documents/pixhawk/mavconn/src/planning/px_waypointplanner.cc; + sourceTree = ""; + }; +} diff --git a/libraries/GCS_MAVLink/missionlib/waypoints.c b/libraries/GCS_MAVLink/missionlib/waypoints.c new file mode 100644 index 0000000000..335f593a9e --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/waypoints.c @@ -0,0 +1,880 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + + ****************************************************************************/ + +#include + +static mavlink_wpm_storage wpm; + +bool debug = true; +bool verbose = true; + + +void mavlink_wpm_init(mavlink_wpm_storage* state) +{ + // Set all waypoints to zero + + // Set count to zero + state->size = 0; + state->max_size = MAVLINK_WPM_MAX_WP_COUNT; + state->current_state = MAVLINK_WPM_STATE_IDLE; + state->current_partner_sysid = 0; + state->current_partner_compid = 0; + state->timestamp_lastaction = 0; + state->timestamp_last_send_setpoint = 0; + state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; + state->delay_setpoint = MAVLINK_WPM_SETPOINT_DELAY_DEFAULT; + state->idle = false; ///< indicates if the system is following the waypoints or is waiting + state->current_active_wp_id = -1; ///< id of current waypoint + state->yaw_reached = false; ///< boolean for yaw attitude reached + state->pos_reached = false; ///< boolean for position reached + state->timestamp_lastoutside_orbit = 0;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value + state->timestamp_firstinside_orbit = 0;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value + +} + +void mavlink_wpm_send_gcs_string(const char* string) +{ + printf("%s",string); +} + +uint64_t mavlink_wpm_get_system_timestamp() +{ + struct timeval tv; + gettimeofday(&tv, NULL); + return ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; +} + +/* + * @brief Sends an waypoint ack message + */ +void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type) +{ + mavlink_message_t msg; + mavlink_waypoint_ack_t wpa; + + wpa.target_system = wpm.current_partner_sysid; + wpa.target_component = wpm.current_partner_compid; + wpa.type = type; + + mavlink_msg_waypoint_ack_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &wpa); + mavlink_wpm_send_message(&msg); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + + if (MAVLINK_WPM_TEXT_FEEDBACK) + { + //printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system); + mavlink_wpm_send_gcs_string("Sent waypoint ACK"); + } +} + +/* + * @brief Broadcasts the new target waypoint and directs the MAV to fly there + * + * This function broadcasts its new active waypoint sequence number and + * sends a message to the controller, advising it to fly to the coordinates + * of the waypoint with a given orientation + * + * @param seq The waypoint sequence number the MAV should fly to. + */ +void mavlink_wpm_send_waypoint_current(uint16_t seq) +{ + if(seq < wpm.size) + { + mavlink_waypoint_t *cur = &(wpm.waypoints[seq]); + + mavlink_message_t msg; + mavlink_waypoint_current_t wpc; + + wpc.seq = cur->seq; + + mavlink_msg_waypoint_current_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &wpc); + mavlink_wpm_send_message(&msg); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("Broadcasted new current waypoint\n"); //printf("Broadcasted new current waypoint %u\n", wpc.seq); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("ERROR: index out of bounds\n"); + } +} + +/* + * @brief Directs the MAV to fly to a position + * + * Sends a message to the controller, advising it to fly to the coordinates + * of the waypoint with a given orientation + * + * @param seq The waypoint sequence number the MAV should fly to. + */ +void mavlink_wpm_send_setpoint(uint16_t seq) +{ + if(seq < wpm.size) + { + mavlink_waypoint_t *cur = &(wpm.waypoints[seq]); + + mavlink_message_t msg; + mavlink_local_position_setpoint_set_t position_control_set_point; + + // Send new NED or ENU setpoint to onbaord autopilot + if (cur->frame == MAV_FRAME_LOCAL_NED || cur->frame == MAV_FRAME_LOCAL_ENU) + { + position_control_set_point.target_system = mavlink_system.sysid; + position_control_set_point.target_component = MAV_COMP_ID_IMU; + position_control_set_point.x = cur->x; + position_control_set_point.y = cur->y; + position_control_set_point.z = cur->z; + position_control_set_point.yaw = cur->param4; + + mavlink_msg_local_position_setpoint_set_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &position_control_set_point); + mavlink_wpm_send_message(&msg); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("No new setpoint set because of invalid coordinate frame of waypoint");//if (verbose) printf("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq); + } + + wpm.timestamp_last_send_setpoint = mavlink_wpm_get_system_timestamp(); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("ERROR: Waypoint index out of bounds\n"); //if (verbose) printf("ERROR: index out of bounds\n"); + } +} + +void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count) +{ + mavlink_message_t msg; + mavlink_waypoint_count_t wpc; + + wpc.target_system = wpm.current_partner_sysid; + wpc.target_component = wpm.current_partner_compid; + wpc.count = count; + + mavlink_msg_waypoint_count_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &wpc); + mavlink_wpm_send_message(&msg); + + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("Sent waypoint count"); //if (verbose) printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); +} + +void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq) +{ + if (seq < wpm.size) + { + mavlink_message_t msg; + mavlink_waypoint_t *wp = &(wpm.waypoints[seq]); + wp->target_system = wpm.current_partner_sysid; + wp->target_component = wpm.current_partner_compid; + mavlink_msg_waypoint_encode(mavlink_system.sysid, mavlink_system.compid, &msg, wp); + mavlink_wpm_send_message(&msg); + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("Sent waypoint"); //if (verbose) printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("ERROR: Waypoint index out of bounds\n"); + } +} + +void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq) +{ + if (seq < wpm.max_size) + { + mavlink_message_t msg; + mavlink_waypoint_request_t wpr; + wpr.target_system = wpm.current_partner_sysid; + wpr.target_component = wpm.current_partner_compid; + wpr.seq = seq; + mavlink_msg_waypoint_request_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &wpr); + mavlink_wpm_send_message(&msg); + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("Sent waypoint request"); //if (verbose) printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("ERROR: Waypoint index exceeds list capacity\n"); + } +} + +/* + * @brief emits a message that a waypoint reached + * + * This function broadcasts a message that a waypoint is reached. + * + * @param seq The waypoint sequence number the MAV has reached. + */ +void mavlink_wpm_send_waypoint_reached(uint16_t seq) +{ + mavlink_message_t msg; + mavlink_waypoint_reached_t wp_reached; + + wp_reached.seq = seq; + + mavlink_msg_waypoint_reached_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &wp_reached); + mavlink_wpm_send_message(&msg); + + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_wpm_send_gcs_string("Sent waypoint reached message"); //if (verbose) printf("Sent waypoint %u reached message\n", wp_reached.seq); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); +} + +//float mavlink_wpm_distance_to_segment(uint16_t seq, float x, float y, float z) +//{ +// if (seq < wpm.size) +// { +// mavlink_waypoint_t *cur = waypoints->at(seq); +// +// const PxVector3 A(cur->x, cur->y, cur->z); +// const PxVector3 C(x, y, z); +// +// // seq not the second last waypoint +// if ((uint16_t)(seq+1) < wpm.size) +// { +// mavlink_waypoint_t *next = waypoints->at(seq+1); +// const PxVector3 B(next->x, next->y, next->z); +// const float r = (B-A).dot(C-A) / (B-A).lengthSquared(); +// if (r >= 0 && r <= 1) +// { +// const PxVector3 P(A + r*(B-A)); +// return (P-C).length(); +// } +// else if (r < 0.f) +// { +// return (C-A).length(); +// } +// else +// { +// return (C-B).length(); +// } +// } +// else +// { +// return (C-A).length(); +// } +// } +// else +// { +// if (verbose) printf("ERROR: index out of bounds\n"); +// } +// return -1.f; +//} + +float mavlink_wpm_distance_to_point(uint16_t seq, float x, float y, float z) +{ +// if (seq < wpm.size) +// { +// mavlink_waypoint_t *cur = waypoints->at(seq); +// +// const PxVector3 A(cur->x, cur->y, cur->z); +// const PxVector3 C(x, y, z); +// +// return (C-A).length(); +// } +// else +// { +// if (verbose) printf("ERROR: index out of bounds\n"); +// } + return -1.f; +} + + +static void mavlink_wpm_message_handler(const mavlink_message_t* msg) +{ + // Handle param messages + //paramClient->handleMAVLinkPacket(msg); + + //check for timed-out operations + struct timeval tv; + gettimeofday(&tv, NULL); + uint64_t now = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; + if (now-wpm.timestamp_lastaction > wpm.timeout && wpm.current_state != MAVLINK_WPM_STATE_IDLE) + { + if (verbose) printf("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm.current_state); + wpm.current_state = MAVLINK_WPM_STATE_IDLE; + wpm.current_count = 0; + wpm.current_partner_sysid = 0; + wpm.current_partner_compid = 0; + wpm.current_wp_id = -1; + + if(wpm.size == 0) + { + wpm.current_active_wp_id = -1; + } + } + + if(now-wpm.timestamp_last_send_setpoint > wpm.delay_setpoint && wpm.current_active_wp_id < wpm.size) + { + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + } + + switch(msg->msgid) + { + case MAVLINK_MSG_ID_ATTITUDE: + { + if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size) + { + mavlink_waypoint_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); + if(wp->frame == MAV_FRAME_LOCAL_ENU || wp->frame == MAV_FRAME_LOCAL_NED) + { + mavlink_attitude_t att; + mavlink_msg_attitude_decode(msg, &att); + float yaw_tolerance = wpm.accept_range_yaw; + //compare current yaw + if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI) + { + if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4) + wpm.yaw_reached = true; + } + else if(att.yaw - yaw_tolerance < 0.0f) + { + float lowerBound = 360.0f + att.yaw - yaw_tolerance; + if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance) + wpm.yaw_reached = true; + } + else + { + float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI; + if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound) + wpm.yaw_reached = true; + } + } + } + break; + } + + case MAVLINK_MSG_ID_LOCAL_POSITION: + { + if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size) + { + mavlink_waypoint_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); + + if(wp->frame == MAV_FRAME_LOCAL_ENU || MAV_FRAME_LOCAL_NED) + { + mavlink_local_position_t pos; + mavlink_msg_local_position_decode(msg, &pos); + //if (debug) printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z); + + wpm.pos_reached = false; + + // compare current position (given in message) with current waypoint + float orbit = wp->param1; + + float dist; + if (wp->param2 == 0) + { + // FIXME segment distance + //dist = mavlink_wpm_distance_to_segment(current_active_wp_id, pos.x, pos.y, pos.z); + } + else + { + dist = mavlink_wpm_distance_to_point(wpm.current_active_wp_id, pos.x, pos.y, pos.z); + } + + if (dist >= 0.f && dist <= orbit && wpm.yaw_reached) + { + wpm.pos_reached = true; + } + } + } + break; + } + +// case MAVLINK_MSG_ID_CMD: // special action from ground station +// { +// mavlink_cmd_t action; +// mavlink_msg_cmd_decode(msg, &action); +// if(action.target == mavlink_system.sysid) +// { +// if (verbose) std::cerr << "Waypoint: received message with action " << action.action << std::endl; +// switch (action.action) +// { +// // case MAV_ACTION_LAUNCH: +// // if (verbose) std::cerr << "Launch received" << std::endl; +// // current_active_wp_id = 0; +// // if (wpm.size>0) +// // { +// // setActive(waypoints[current_active_wp_id]); +// // } +// // else +// // if (verbose) std::cerr << "No launch, waypointList empty" << std::endl; +// // break; +// +// // case MAV_ACTION_CONTINUE: +// // if (verbose) std::c +// // err << "Continue received" << std::endl; +// // idle = false; +// // setActive(waypoints[current_active_wp_id]); +// // break; +// +// // case MAV_ACTION_HALT: +// // if (verbose) std::cerr << "Halt received" << std::endl; +// // idle = true; +// // break; +// +// // default: +// // if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl; +// // break; +// } +// } +// break; +// } + + case MAVLINK_MSG_ID_WAYPOINT_ACK: + { + mavlink_waypoint_ack_t wpa; + mavlink_msg_waypoint_ack_decode(msg, &wpa); + + if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wpa.target_system == mavlink_system.sysid && wpa.target_component == mavlink_system.compid)) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) + { + if (wpm.current_wp_id == wpm.size-1) + { + if (verbose) printf("Received Ack after having sent last waypoint, going to state MAVLINK_WPM_STATE_IDLE\n"); + wpm.current_state = MAVLINK_WPM_STATE_IDLE; + wpm.current_wp_id = 0; + } + } + } + else + { + if (verbose) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: + { + mavlink_waypoint_set_current_t wpc; + mavlink_msg_waypoint_set_current_decode(msg, &wpc); + + if(wpc.target_system == mavlink_system.sysid && wpc.target_component == mavlink_system.compid) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { + if (wpc.seq < wpm.size) + { + if (verbose) printf("Received MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT\n"); + wpm.current_active_wp_id = wpc.seq; + uint32_t i; + for(i = 0; i < wpm.size; i++) + { + if (i == wpm.current_active_wp_id) + { + wpm.waypoints[i].current = true; + } + else + { + wpm.waypoints[i].current = false; + } + } + if (verbose) printf("New current waypoint %u\n", wpm.current_active_wp_id); + wpm.yaw_reached = false; + wpm.pos_reached = false; + mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id); + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + wpm.timestamp_firstinside_orbit = 0; + } + else + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: Index out of bounds\n"); + } + } + else + { + if (verbose) printf("IGNORED WAYPOINT COMMAND BECAUSE NOT IN IDLE STATE\n"); + } + } + else + { + if (verbose) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: + { + mavlink_waypoint_request_list_t wprl; + mavlink_msg_waypoint_request_list_decode(msg, &wprl); + if(wprl.target_system == mavlink_system.sysid && wprl.target_component == mavlink_system.compid) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) + { + if (wpm.size > 0) + { + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_IDLE) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); + wpm.current_state = MAVLINK_WPM_STATE_SENDLIST; + wpm.current_wp_id = 0; + wpm.current_partner_sysid = msg->sysid; + wpm.current_partner_compid = msg->compid; + } + else + { + if (verbose) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid); + } + wpm.current_count = wpm.size; + mavlink_wpm_send_waypoint_count(msg->sysid,msg->compid, wpm.current_count); + } + else + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST because i'm doing something else already (state=%i).\n", wpm.current_state); + } + } + else + { + if (verbose) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT MISMATCH\n"); + } + + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_REQUEST: + { + mavlink_waypoint_request_t wpr; + mavlink_msg_waypoint_request_decode(msg, &wpr); + if(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid && wpr.target_system == mavlink_system.sysid && wpr.target_component == mavlink_system.compid) + { + wpm.timestamp_lastaction = now; + + //ensure that we are in the correct state and that the first request has id 0 and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint) + if ((wpm.current_state == MAVLINK_WPM_STATE_SENDLIST && wpr.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && (wpr.seq == wpm.current_wp_id || wpr.seq == wpm.current_wp_id + 1) && wpr.seq < wpm.size)) + { + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id + 1) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + + wpm.current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; + wpm.current_wp_id = wpr.seq; + mavlink_wpm_send_waypoint(wpm.current_partner_sysid, wpm.current_partner_compid, wpr.seq); + } + else + { + if (verbose) + { + if (!(wpm.current_state == MAVLINK_WPM_STATE_SENDLIST || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS)) { printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because i'm doing something else already (state=%i).\n", wpm.current_state); break; } + else if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) + { + if (wpr.seq != 0) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq); + } + else if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) + { + if (wpr.seq != wpm.current_wp_id && wpr.seq != wpm.current_wp_id + 1) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, wpm.current_wp_id, wpm.current_wp_id+1); + else if (wpr.seq >= wpm.size) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq); + } + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST - FIXME: missed error description\n"); + } + } + } + else + { + //we we're target but already communicating with someone else + if((wpr.target_system == mavlink_system.sysid && wpr.target_component == mavlink_system.compid) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid)) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, wpm.current_partner_sysid); + } + else + { + if (verbose) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); + } + + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_COUNT: + { + mavlink_waypoint_count_t wpc; + mavlink_msg_waypoint_count_decode(msg, &wpc); + if(wpc.target_system == mavlink_system.sysid && wpc.target_component == mavlink_system.compid) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id == 0)) + { + if (wpc.count > 0) + { + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_IDLE) printf("Got MAVLINK_MSG_ID_WAYPOINT_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST\n", wpc.count, msg->sysid); + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT_COUNT (%u) again from %u\n", wpc.count, msg->sysid); + + wpm.current_state = MAVLINK_WPM_STATE_GETLIST; + wpm.current_wp_id = 0; + wpm.current_partner_sysid = msg->sysid; + wpm.current_partner_compid = msg->compid; + wpm.current_count = wpc.count; + + printf("clearing receive buffer and readying for receiving waypoints\n"); + wpm.rcv_size = 0; + //while(waypoints_receive_buffer->size() > 0) +// { +// delete waypoints_receive_buffer->back(); +// waypoints_receive_buffer->pop_back(); +// } + + mavlink_wpm_send_waypoint_request(wpm.current_partner_sysid, wpm.current_partner_compid, wpm.current_wp_id); + } + else if (wpc.count == 0) + { + printf("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE\n"); + wpm.rcv_size = 0; + //while(waypoints_receive_buffer->size() > 0) +// { +// delete waypoints->back(); +// waypoints->pop_back(); +// } + wpm.current_active_wp_id = -1; + wpm.yaw_reached = false; + wpm.pos_reached = false; + break; + + } + else + { + if (verbose) printf("Ignoring MAVLINK_MSG_ID_WAYPOINT_COUNT from %u with count of %u\n", msg->sysid, wpc.count); + } + } + else + { + if (verbose && !(wpm.current_state == MAVLINK_WPM_STATE_IDLE || wpm.current_state == MAVLINK_WPM_STATE_GETLIST)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT because i'm doing something else already (state=%i).\n", wpm.current_state); + else if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id != 0) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT because i'm already receiving waypoint %u.\n", wpm.current_wp_id); + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT - FIXME: missed error description\n"); + } + } + else + { + if (verbose) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); + } + + } + break; + + case MAVLINK_MSG_ID_WAYPOINT: + { + mavlink_waypoint_t wp; + mavlink_msg_waypoint_decode(msg, &wp); + + if (verbose) printf("GOT WAYPOINT!"); + + if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wp.target_system == mavlink_system.sysid && wp.target_component == mavlink_system.compid)) + { + wpm.timestamp_lastaction = now; + + //ensure that we are in the correct state and that the first waypoint has id 0 and the following waypoints have the correct ids + if ((wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wp.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id && wp.seq < wpm.current_count)) + { + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST) printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid); + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id) printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u\n", wp.seq, msg->sysid); + if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq-1 == wpm.current_wp_id) printf("Got MAVLINK_MSG_ID_WAYPOINT %u (again) from %u\n", wp.seq, msg->sysid); + + wpm.current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS; + mavlink_waypoint_t* newwp = &(wpm.rcv_waypoints[wp.seq]); + memcpy(newwp, &wp, sizeof(mavlink_waypoint_t)); + + wpm.current_wp_id = wp.seq + 1; + + if (verbose) printf ("Added new waypoint to list. X= %f\t Y= %f\t Z= %f\t Yaw= %f\n", newwp->x, newwp->y, newwp->z, newwp->param4); + + if(wpm.current_wp_id == wpm.current_count && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) + { + if (verbose) printf("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm.current_count); + + mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0); + + if (wpm.current_active_wp_id > wpm.rcv_size-1) + { + wpm.current_active_wp_id = wpm.rcv_size-1; + } + + // switch the waypoints list + // FIXME CHECK!!! + for (int i = 0; i < wpm.current_count; ++i) + { + wpm.waypoints[i] = wpm.rcv_waypoints[i]; + } + wpm.size = wpm.current_count; + + //get the new current waypoint + uint32_t i; + for(i = 0; i < wpm.size; i++) + { + if (wpm.waypoints[i].current == 1) + { + wpm.current_active_wp_id = i; + //if (verbose) printf("New current waypoint %u\n", current_active_wp_id); + wpm.yaw_reached = false; + wpm.pos_reached = false; + mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id); + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + wpm.timestamp_firstinside_orbit = 0; + break; + } + } + + if (i == wpm.size) + { + wpm.current_active_wp_id = -1; + wpm.yaw_reached = false; + wpm.pos_reached = false; + wpm.timestamp_firstinside_orbit = 0; + } + + wpm.current_state = MAVLINK_WPM_STATE_IDLE; + } + else + { + mavlink_wpm_send_waypoint_request(wpm.current_partner_sysid, wpm.current_partner_compid, wpm.current_wp_id); + } + } + else + { + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { + //we're done receiving waypoints, answer with ack. + mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0); + printf("Received MAVLINK_MSG_ID_WAYPOINT while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n"); + } + if (verbose) + { + if (!(wpm.current_state == MAVLINK_WPM_STATE_GETLIST || wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)) { printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u because i'm doing something else already (state=%i).\n", wp.seq, wpm.current_state); break; } + else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST) + { + if(!(wp.seq == 0)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the first waypoint ID (%u) was not 0.\n", wp.seq); + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + } + else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) + { + if (!(wp.seq == wpm.current_wp_id)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm.current_wp_id); + else if (!(wp.seq < wpm.current_count)) printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the waypoint ID (%u) was out of bounds.\n", wp.seq); + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + } + else printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + } + } + } + else + { + //we we're target but already communicating with someone else + if((wp.target_system == mavlink_system.sysid && wp.target_component == mavlink_system.compid) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && wpm.current_state != MAVLINK_WPM_STATE_IDLE) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm.current_partner_sysid); + } + else if(wp.target_system == mavlink_system.sysid && wp.target_component == mavlink_system.compid) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid); + } + } + break; + } + + case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: + { + mavlink_waypoint_clear_all_t wpca; + mavlink_msg_waypoint_clear_all_decode(msg, &wpca); + + if(wpca.target_system == mavlink_system.sysid && wpca.target_component == mavlink_system.compid && wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { + wpm.timestamp_lastaction = now; + + if (verbose) printf("Got MAVLINK_MSG_ID_WAYPOINT_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid); + // Delete all waypoints + wpm.size = 0; + wpm.current_active_wp_id = -1; + wpm.yaw_reached = false; + wpm.pos_reached = false; + } + else if (wpca.target_system == mavlink_system.sysid && wpca.target_component == mavlink_system.compid && wpm.current_state != MAVLINK_WPM_STATE_IDLE) + { + if (verbose) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, wpm.current_state); + } + break; + } + + default: + { + if (debug) printf("Waypoint: received message of unknown type"); + break; + } + } + + //check if the current waypoint was reached + if (wpm.pos_reached /*wpm.yaw_reached &&*/ && !wpm.idle) + { + if (wpm.current_active_wp_id < wpm.size) + { + mavlink_waypoint_t *cur_wp = &(wpm.waypoints[wpm.current_active_wp_id]); + + if (wpm.timestamp_firstinside_orbit == 0) + { + // Announce that last waypoint was reached + if (verbose) printf("*** Reached waypoint %u ***\n", cur_wp->seq); + mavlink_wpm_send_waypoint_reached(cur_wp->seq); + wpm.timestamp_firstinside_orbit = now; + } + + // check if the MAV was long enough inside the waypoint orbit + //if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000)) + if(now-wpm.timestamp_firstinside_orbit >= cur_wp->param2*1000) + { + if (cur_wp->autocontinue) + { + cur_wp->current = 0; + if (wpm.current_active_wp_id == wpm.size - 1 && wpm.size > 1) + { + //the last waypoint was reached, if auto continue is + //activated restart the waypoint list from the beginning + wpm.current_active_wp_id = 1; + } + else + { + if ((uint16_t)(wpm.current_active_wp_id + 1) < wpm.size) + wpm.current_active_wp_id++; + } + + // Fly to next waypoint + wpm.timestamp_firstinside_orbit = 0; + mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id); + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + wpm.waypoints[wpm.current_active_wp_id].current = true; + wpm.pos_reached = false; + wpm.yaw_reached = false; + if (verbose) printf("Set new waypoint (%u)\n", wpm.current_active_wp_id); + } + } + } + } + else + { + wpm.timestamp_lastoutside_orbit = now; + } +} + diff --git a/libraries/GCS_MAVLink/missionlib/waypoints.h b/libraries/GCS_MAVLink/missionlib/waypoints.h new file mode 100644 index 0000000000..4bc32a14a4 --- /dev/null +++ b/libraries/GCS_MAVLink/missionlib/waypoints.h @@ -0,0 +1,91 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + + ****************************************************************************/ + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ +#include +#include + +// FIXME XXX - TO BE MOVED TO XML +enum MAVLINK_WPM_STATES +{ + MAVLINK_WPM_STATE_IDLE = 0, + MAVLINK_WPM_STATE_SENDLIST, + MAVLINK_WPM_STATE_SENDLIST_SENDWPS, + MAVLINK_WPM_STATE_GETLIST, + MAVLINK_WPM_STATE_GETLIST_GETWPS, + MAVLINK_WPM_STATE_GETLIST_GOTALL, + MAVLINK_WPM_STATE_ENUM_END +}; + +enum MAVLINK_WPM_CODES +{ + MAVLINK_WPM_CODE_OK = 0, + MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS, + MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, + MAVLINK_WPM_CODE_ENUM_END +}; + + +/* WAYPOINT MANAGER - MISSION LIB */ + +#define MAVLINK_WPM_MAX_WP_COUNT 100 +#define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates +#define MAVLINK_WPM_TEXT_FEEDBACK 1 ///< Report back status information as text +#define MAVLINK_WPM_SYSTEM_ID 1 +#define MAVLINK_WPM_COMPONENT_ID 1 +#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 2000000 +#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 +#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40 + + +struct mavlink_wpm_storage { + mavlink_waypoint_t waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Currently active waypoints +#ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE + mavlink_waypoint_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints +#endif + uint16_t size; + uint16_t max_size; + uint16_t rcv_size; + enum MAVLINK_WPM_STATES current_state; + uint16_t current_wp_id; ///< Waypoint in current transmission + uint16_t current_active_wp_id; ///< Waypoint the system is currently heading towards + uint16_t current_count; + uint8_t current_partner_sysid; + uint8_t current_partner_compid; + uint64_t timestamp_lastaction; + uint64_t timestamp_last_send_setpoint; + uint64_t timestamp_firstinside_orbit; + uint64_t timestamp_lastoutside_orbit; + uint32_t timeout; + uint32_t delay_setpoint; + float accept_range_yaw; + float accept_range_distance; + bool yaw_reached; + bool pos_reached; + bool idle; +}; + +typedef struct mavlink_wpm_storage mavlink_wpm_storage; + +void mavlink_wpm_init(mavlink_wpm_storage* state); + +void mavlink_wpm_message_handler(const mavlink_message_t* msg); \ No newline at end of file diff --git a/libraries/GCS_MAVLink/sync b/libraries/GCS_MAVLink/sync index b4631e2943..424c243930 100755 --- a/libraries/GCS_MAVLink/sync +++ b/libraries/GCS_MAVLink/sync @@ -1,8 +1,5 @@ #!/bin/sh -branch="dev" -# temporarily using roi branch instead of master -# this branch will be deleted soon so switch it back -# to master then +branch="master" trap exit ERR rm -rf _tmp git clone git://github.com/pixhawk/mavlink.git -b $branch _tmp