diff --git a/README b/README index aad1ba690ea62c443ba63f3a0aeacfa1ce35ca94..1d08b8244e01e58d383ec5959c5a6b5f85cddd2b 100644 --- a/README +++ b/README @@ -1,3 +1,4 @@ +maah QGroundControl Open Source Micro Air Vehicle Ground Control Station Project: @@ -36,7 +37,7 @@ Build QGroundControl -------------------- 1) From the terminal go to the `groundcontrol` directory -2) Run `qmake` +2) Run `qmake -spec macx-g++` 3) Run `make -j8` diff --git a/dongfang_qgroundcontrol_notes.txt b/dongfang_qgroundcontrol_notes.txt new file mode 100644 index 0000000000000000000000000000000000000000..40fcc46d076944deeac1b1ee22c165f4cfa56651 --- /dev/null +++ b/dongfang_qgroundcontrol_notes.txt @@ -0,0 +1,90 @@ +From where is the 3D mouse used? + + +Comm folder: +============ + +LinkInterface is a QThread. Appears to describe an interface on the host system (TCP port, serial port, ....). + Does it suppport multiple connections? +SerialLinkInterface: Extension of above +SerialLink: Implementation + +XBeeLinkInterface: Extension of LinkInterface (but without other serial stuff than baudrate, is the rest assumed?) +XBeeLink: Implementation (with address resetting probably it's Series 1) + +UDPLink: UDP implementation. Port is defaulted. + +MAVLinkSimulationLink: Simulation/dummy implementation of LinkInterface. Does some file IO. +MAVLinkSimulationUAV: Simulation/dummy basic (remote) UAV state (minus mission state) for MAVLinkSimulationLink. +MAVLinkSimulationWaypointPlanner: imulation/dummy basic (remote) UAV mission state for MAVLinkSimulationLink. + + +ProtocolInterface describes a protocol. Major method: + virtual void receiveBytes(LinkInterface *link, QByteArray b) = 0; + +MavlinkProtocol: MAVLink implementation of ProtocolInterface + + +Parameter: Identity of a parameter (the value types are not handled here. Oddly there is no type metainfo either) +ParameterList: Is pretty much what the name impiles. +QGCParamID: Wrapper if parameter text IDs, conversion to byte* and back + +QGCHilLink: Link to a HIL external system + QCGFlightGearLink, QGCJSBSimLink, QGCXPlaneLink : Implementations of QGCHilLink + + +QGCMAVLink: Nothing more than in include to raw mavlink.h + + +input folder: +============= +Some exotic input devices + + + +uas folder: +=========== +UAS.h: Local UAV model. Claims to support some sort of RPC. Uses some properties with notifications. Assumes MAVLink. +Some methods: + int getUASID() const; // the systemId + QList* getLinks(); // it knows its links + + virtual void receiveMessage(LinkInterface* link, mavlink_message_t message); + + float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs) + float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS + +Some fields: + bool positionLock; ///< Status if position information is available or not + double localX; // (what is this?) + double localY; + double localZ; + double latitude; ///< Global latitude as estimated by position estimator + double longitude; ///< Global longitude as estimated by position estimator + double altitude; ///< Global altitude as estimated by position estimator + double satelliteCount; ///< Number of satellites visible to raw GPS + bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position + double latitude_gps; ///< Global latitude as estimated by raw GPS + double longitude_gps; ///< Global longitude as estimated by raw GPS + double altitude_gps; ///< Global altitude as estimated by raw GPS + + and lots ans lots more... + + +*MAV.h: Implementations of UAS + + +QGCUASParamManager.h: A mixture of a widget and a parameter up/download state machine. Has a reference to its associated UAV. + +UASWaypointManager: API to waypoint / mission control. Not a widget. Has a reference to its associated UAV. + +UASManager.h: Singleton interface to all UASs on all interfaces. Maintains a single selected/active UAS. + +Ideas to do +TCPLink +XBee Series2 implementation +Less stress on uplink +Get rid of hardcoded SystemId of 255 +Quick View should print all altitudes (GPS, mix, ground and/or home), letting user see errors. +Console debugging is hopefully removed? + diff --git a/dongfang_qgroundcontrol_wishlist.txt b/dongfang_qgroundcontrol_wishlist.txt new file mode 100644 index 0000000000000000000000000000000000000000..f55ba1dc24dcc2a8f367946a436e72672ac7bec3 --- /dev/null +++ b/dongfang_qgroundcontrol_wishlist.txt @@ -0,0 +1,23 @@ +Major +1) Absolute altitude should absolutely work. Also in face of bad GPS init. + How does the mission planning part work with that, how is alt. stored in waypoints? + When is home altitude stored in the UAV? + +2) Some people have worse datalinks than average - eg. slow or noisy telemetry. GPRS data also easily gets + flooded. All data rates should be configurable and uplinks eased off a little. + +3) Some streams should be sent always even if not in use. For example using RC override and then stopping + using it: If the UAV does not received the final RC override message with zero values for all channels, + it will not get out of RC override. A solution is to make the message non final, repeating it every + now and then. + +Minor +1) I would like to see initial dummy values for eg. battery voltage go away and be replaced by "unknown". + Dummy values confuse, you won't know if your sensors and link are working or not. + +2) Suggestion if the DO_JUMP behavior of APM today (where DO_JUMP requires a waypoint command after it): + Modify APM code so DO_JUMP is regarded a navigation command. Make non navigation commands appear in + planning as sub commands of navigation commands (indent them). Easier to understand. + +3) Old style audio with signals/bells/beeps / Morse may be prefered by some. Maybe add slots'n'signals for + all audio and different implementation types (speech, beep, ...). Or a generic operator messaging thing. diff --git a/files/ardupilotmega/arduplane.pdef.xml b/files/ardupilotmega/arduplane.pdef.xml index ca6d297927fadd7fc7473cef4df2f827150a78bb..d96d60205a5d710223964a2e486ba00454fac6ce 100644 --- a/files/ardupilotmega/arduplane.pdef.xml +++ b/files/ardupilotmega/arduplane.pdef.xml @@ -220,6 +220,12 @@ ReturnToLaunch + +Volts + + +mAh + Disabled @@ -377,7 +383,12 @@ - + + +Disabled +Default +Default+IMU + @@ -488,7 +499,7 @@ seconds -0 4000 +0 8000 1 Centimeters @@ -500,7 +511,7 @@ -XL-EZ0 +XL-EZ0 / XL-EZ4 LV-EZ0 XLL-EZ0 HRLV @@ -540,7 +551,7 @@ - + mAh @@ -557,7 +568,7 @@ 0 20 -.1 +0.1 @@ -628,7 +639,7 @@ ms -10 200 +20 200 10 Centimeters/Second @@ -769,6 +780,13 @@ + +Disabled +Default +Default+IMU +Default+Motors +Default+INav + 1 10 @@ -824,7 +842,6 @@ 0 32767 -0 32767 Plus X @@ -840,18 +857,47 @@ RTL Save Trim Save WP +Multi Mode Camera Trigger Sonar +Fence +ResetToArmedYaw - -1 90 -1 -Degrees/Second + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Multi Mode +Camera Trigger +Sonar +Fence +ResetToArmedYaw + + + + +Disabled +Enabled + + + +0 10 + + +0 10 + + +0 10 -125,400,490 -Hertz (Hz) +50 490 +1 +Hz 1 10 @@ -888,53 +934,192 @@ GPS Nav Blink - + +0.08 0.20 + + +0.01 0.5 + + +0 500 +PWM + + 0.001 0.008 - + +0.08 0.20 + + +0.01 0.5 + + +0 500 +PWM + + 0.001 0.008 - + +0.150 0.250 + + +0.010 0.020 + + +0 500 +PWM + + 0.000 0.001 - + +2.000 6.000 + + +0.020 0.060 + + +0 4500 +Centi-Degrees + + 0.200 0.600 - + +2.000 6.000 + + +0.020 0.060 + + +0 4500 +Centi-Degrees + + 0.200 0.600 - + +1.000 8.000 + + +0.000 0.100 + + +0 500 +cm/s/s + + 0.000 0.400 - + +0.500 1.500 + + +0.000 3.000 + + +0 500 +PWM + + 0.000 0.400 - + +2.000 3.000 + + +0.250 0.750 + + +0 4500 +Centi-Degrees + + 0.100 0.140 - + +2.000 3.000 + + +0.250 0.750 + + +0 4500 +Centi-Degrees + + 0.100 0.140 - + +3.000 6.000 + + +0.000 0.100 + + 0 4500 +Centi-Degrees/Sec - + +3.000 6.000 + + +0.000 0.100 + + 0 4500 +Centi-Degrees/Sec + + +3.000 6.000 + + +0.000 0.100 - + 0 4500 +Centi-Degrees/Sec - + +1.000 3.000 + + +0.000 0.100 + + 0 500 +cm/s + + +0.100 0.300 - + +0.000 0.100 + + 0 3000 +cm/s + + +0.100 0.300 + + +0.000 0.100 - + 0 3000 +cm/s + + +Disabled +Default +Default+IMU + + MANUAL @@ -1022,7 +1207,7 @@ - + mAh @@ -1215,7 +1400,15 @@ meters - + + +1 + + +1 + + + Servo @@ -1361,32 +1554,7 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - - -Reversed -Normal - - - - - - - + Disabled Manual @@ -1411,32 +1579,9 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - - -Reversed -Normal - - - - - - + + Disabled Manual @@ -1461,32 +1606,7 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - - -Reversed -Normal - - - - - - - + Disabled Manual @@ -1511,32 +1631,9 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - - -Reversed -Normal - - - - - - + + Disabled Manual @@ -1561,32 +1658,7 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - - -Reversed -Normal - - - - - - - + Disabled Manual @@ -1611,32 +1683,61 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - + + + -Reversed -Normal +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput - + + +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput + - - + + Disabled Manual @@ -1661,28 +1762,134 @@ ElevatorWithInput - -800 2200 -1 -ms + + +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput + - -800 2200 -1 -ms + + + + +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput + - -800 2200 -1 -ms + + +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput + - + + + -Reversed -Normal +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput - + + +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput + @@ -1711,29 +1918,31 @@ ElevatorWithInput - -800 2200 -1 -ms - - -800 2200 -1 -ms - - -800 2200 -1 -ms - - + -Reversed -Normal +Disabled +Manual +Flap +Flap_auto +Aileron +flaperon +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput - - @@ -1809,7 +2018,15 @@ - + +-400 400 +1 + + +-400 400 +1 + + -400 400 1 @@ -1844,7 +2061,17 @@ 1 - + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + -1000 1000 1 Offset per Amp or at Full Throttle @@ -1882,11 +2109,34 @@ - + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-300 300 +m/s/s + + -300 300 m/s/s - + +-300 300 +m/s/s + + +rad/s + + +rad/s + + rad/s @@ -1907,6 +2157,10 @@ .01 + +Disabled +Enabled + 0.1 0.4 @@ -1921,7 +2175,16 @@ 1 m/s - + +-10 10 +Radians + + +-10 10 +Radians + + +-10 10 Radians @@ -1953,12 +2216,13 @@ Pitch270 - + 0.001 0.5 .01 0 10 +1 @@ -2002,17 +2266,47 @@ GPS_point - + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees @@ -2101,17 +2395,47 @@ GPS_point - + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees @@ -2168,26 +2492,126 @@ -Disabled -RC5 -RC6 -RC7 -RC8 +Disabled +RC5 +RC6 +RC7 +RC8 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0 100 +1 + + + + +800 2200 +1 +ms + + +800 2200 +1 +ms + + +800 2200 +1 +ms + + + +Reversed +Normal + + + + + + + +800 2200 +1 +ms + + +800 2200 +1 +ms + + +800 2200 +1 +ms + + + +Reversed +Normal + + + + + + + +800 2200 +1 +ms + + +800 2200 +1 +ms + + +800 2200 +1 +ms + + + +Reversed +Normal - --18000 17999 + + + + + +800 2200 1 -Centi-Degrees +ms - --18000 17999 + +800 2200 1 -Centi-Degrees +ms - -0 100 + +800 2200 1 +ms + + + +Reversed +Normal + + + @@ -2711,7 +3135,15 @@ - + +-400 400 +1 + + +-400 400 +1 + + -400 400 1 @@ -2746,7 +3178,17 @@ 1 - + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + -1000 1000 1 Offset per Amp or at Full Throttle @@ -2781,95 +3223,79 @@ - - -0 10 -0.1 - - -0 10 -0.1 + + - - - -0 2000 -50 -Centimeters/Second + +0.8 1.2 - -100 1000 -1 -Centimeters + +0.8 1.2 - -0 1000 -50 -Centimeters/Second + +0.8 1.2 - -0 1000 -50 -Centimeters/Second + +-300 300 +m/s/s - -0 2000 -50 -Centimeters/Second + +-300 300 +m/s/s - - - -0 2000 -50 -Centimeters/Second + +-300 300 +m/s/s - -100 1000 -1 -Centimeters + +rad/s - -0 1000 -50 -Centimeters/Second + +rad/s - -0 1000 -50 -Centimeters/Second + +rad/s - -0 2000 -50 -Centimeters/Second + + +Default +5Hz +10Hz +20Hz +42Hz +98Hz + +Hz - - -0 2000 -50 -Centimeters/Second + + +0 10 +0.1 - -100 1000 -1 -Centimeters + +0 10 +0.1 - -0 1000 -50 -Centimeters/Second + + + +0 10 +0.1 - -0 1000 -50 -Centimeters/Second + +0 10 +0.1 - -0 2000 -50 -Centimeters/Second + + + +0 10 +0.1 + + +0 10 +0.1 @@ -2878,6 +3304,10 @@ .01 + +Disabled +Enabled + 0.1 0.4 @@ -2892,7 +3322,16 @@ 1 m/s - + +-10 10 +Radians + + +-10 10 +Radians + + +-10 10 Radians @@ -2924,12 +3363,13 @@ Pitch270 - + 0.001 0.5 .01 0 10 +1 @@ -2942,17 +3382,47 @@ GPS_point - + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees @@ -3041,17 +3511,47 @@ GPS_point - + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees - + -18000 17999 1 Centi-Degrees @@ -3130,36 +3630,22 @@ 1 - - - -Disabled -Enabled - + + +1 - - -None -Altitude -Circle -Altitude and Circle - + +1 - + + + -Report Only -RTL or Land +Disabled +ShowSlipe +ShowOverruns - -10 1000 -1 -Meters - - -0 10000 -Meters - @@ -3308,14 +3794,76 @@ 1 + + + + +meters/Volt +0.001 + + +Volts +0.001 + + + +Linear +Inverted +Hyperbolic + + + +centimeters +1 + + +centimeters +1 + + + +Disabled +Enabled + + + + + +milliseconds +1 + + - + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-300 300 +m/s/s + + -300 300 m/s/s - + +-300 300 +m/s/s + + +rad/s + + +rad/s + + rad/s @@ -3336,6 +3884,10 @@ .01 + +Disabled +Enabled + 0.1 0.4 @@ -3350,7 +3902,16 @@ 1 m/s - + +-10 10 +Radians + + +-10 10 +Radians + + +-10 10 Radians @@ -3382,12 +3943,13 @@ Pitch270 - + 0.001 0.5 .01 0 10 +1 diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index afc57c443f10ff66a4e511d620236512d221ad3a..7073045599df1263febd23590aa524da5b6f7547 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 88, 44, 9, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 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, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 234, 73, 181, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 5, 212, 185, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 234, 73, 181, 22, 83, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -109,7 +109,7 @@ enum FENCE_BREACH { FENCE_BREACH_NONE=0, /* No last fence breach | */ FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ - FENCE_BREACH_MAXALT=2, /* Breached minimum altitude | */ + FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ FENCE_BREACH_ENUM_END=4, /* | */ }; @@ -178,6 +178,7 @@ enum LIMIT_MODULE #include "./mavlink_msg_data32.h" #include "./mavlink_msg_data64.h" #include "./mavlink_msg_data96.h" +#include "./mavlink_msg_rangefinder.h" #ifdef __cplusplus } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h index a59f89aeeba480b16e89ac4e252ca6428b620522..d9d2ccb04181f8896b31e1574fafd0e04002097b 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h @@ -16,6 +16,9 @@ typedef struct __mavlink_ahrs_t #define MAVLINK_MSG_ID_AHRS_LEN 28 #define MAVLINK_MSG_ID_163_LEN 28 +#define MAVLINK_MSG_ID_AHRS_CRC 127 +#define MAVLINK_MSG_ID_163_CRC 127 + #define MAVLINK_MESSAGE_INFO_AHRS { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t componen float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_AHRS_LEN]; _mav_put_float(buf, 0, omegaIx); _mav_put_float(buf, 4, omegaIy); _mav_put_float(buf, 8, omegaIz); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t componen _mav_put_float(buf, 20, error_rp); _mav_put_float(buf, 24, error_yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN); #else mavlink_ahrs_t packet; packet.omegaIx = omegaIx; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t componen packet.error_rp = error_rp; packet.error_yaw = error_yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AHRS; - return mavlink_finalize_message(msg, system_id, component_id, 28, 127); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t com float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_AHRS_LEN]; _mav_put_float(buf, 0, omegaIx); _mav_put_float(buf, 4, omegaIy); _mav_put_float(buf, 8, omegaIz); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t com _mav_put_float(buf, 20, error_rp); _mav_put_float(buf, 24, error_yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN); #else mavlink_ahrs_t packet; packet.omegaIx = omegaIx; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t com packet.error_rp = error_rp; packet.error_yaw = error_yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AHRS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 127); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t compon static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_AHRS_LEN]; _mav_put_float(buf, 0, omegaIx); _mav_put_float(buf, 4, omegaIy); _mav_put_float(buf, 8, omegaIz); @@ -164,7 +175,11 @@ static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, _mav_put_float(buf, 20, error_rp); _mav_put_float(buf, 24, error_yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28, 127); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN); +#endif #else mavlink_ahrs_t packet; packet.omegaIx = omegaIx; @@ -175,7 +190,11 @@ static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, packet.error_rp = error_rp; packet.error_yaw = error_yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28, 127); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, MAVLINK_MSG_ID_AHRS_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg); ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg); #else - memcpy(ahrs, _MAV_PAYLOAD(msg), 28); + memcpy(ahrs, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AHRS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h index ea640c4fb0b33ed817578a0c0fa05b612c546c04..c6c76245139f24354affb49931cb88ef3d28ee79 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h @@ -15,6 +15,9 @@ typedef struct __mavlink_ap_adc_t #define MAVLINK_MSG_ID_AP_ADC_LEN 12 #define MAVLINK_MSG_ID_153_LEN 12 +#define MAVLINK_MSG_ID_AP_ADC_CRC 188 +#define MAVLINK_MSG_ID_153_CRC 188 + #define MAVLINK_MESSAGE_INFO_AP_ADC { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_AP_ADC_LEN]; _mav_put_uint16_t(buf, 0, adc1); _mav_put_uint16_t(buf, 2, adc2); _mav_put_uint16_t(buf, 4, adc3); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon _mav_put_uint16_t(buf, 8, adc5); _mav_put_uint16_t(buf, 10, adc6); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN); #else mavlink_ap_adc_t packet; packet.adc1 = adc1; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon packet.adc5 = adc5; packet.adc6 = adc6; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AP_ADC; - return mavlink_finalize_message(msg, system_id, component_id, 12, 188); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AP_ADC_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_AP_ADC_LEN]; _mav_put_uint16_t(buf, 0, adc1); _mav_put_uint16_t(buf, 2, adc2); _mav_put_uint16_t(buf, 4, adc3); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c _mav_put_uint16_t(buf, 8, adc5); _mav_put_uint16_t(buf, 10, adc6); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN); #else mavlink_ap_adc_t packet; packet.adc1 = adc1; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c packet.adc5 = adc5; packet.adc6 = adc6; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AP_ADC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 188); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AP_ADC_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t comp static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_AP_ADC_LEN]; _mav_put_uint16_t(buf, 0, adc1); _mav_put_uint16_t(buf, 2, adc2); _mav_put_uint16_t(buf, 4, adc3); @@ -154,7 +165,11 @@ static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1 _mav_put_uint16_t(buf, 8, adc5); _mav_put_uint16_t(buf, 10, adc6); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12, 188); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN); +#endif #else mavlink_ap_adc_t packet; packet.adc1 = adc1; @@ -164,7 +179,11 @@ static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1 packet.adc5 = adc5; packet.adc6 = adc6; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12, 188); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, MAVLINK_MSG_ID_AP_ADC_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavli ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg); ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg); #else - memcpy(ap_adc, _MAV_PAYLOAD(msg), 12); + memcpy(ap_adc, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AP_ADC_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h index 359201c8cfbcfced3a5bc031c3d348aa467ed950..c75358526764784ce8f42e6bdea52cf99658008c 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h @@ -12,6 +12,9 @@ typedef struct __mavlink_data16_t #define MAVLINK_MSG_ID_DATA16_LEN 18 #define MAVLINK_MSG_ID_169_LEN 18 +#define MAVLINK_MSG_ID_DATA16_CRC 234 +#define MAVLINK_MSG_ID_169_CRC 234 + #define MAVLINK_MSG_DATA16_FIELD_DATA_LEN 16 #define MAVLINK_MESSAGE_INFO_DATA16 { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_data16_pack(uint8_t system_id, uint8_t compon uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_DATA16_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN); #else mavlink_data16_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA16; - return mavlink_finalize_message(msg, system_id, component_id, 18, 234); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA16_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_data16_pack_chan(uint8_t system_id, uint8_t c uint8_t type,uint8_t len,const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_DATA16_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN); #else mavlink_data16_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA16; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 234); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA16_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_data16_encode(uint8_t system_id, uint8_t comp static inline void mavlink_msg_data16_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_DATA16_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, 18, 234); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN); +#endif #else mavlink_data16_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, 18, 234); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, MAVLINK_MSG_ID_DATA16_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_data16_decode(const mavlink_message_t* msg, mavli data16->len = mavlink_msg_data16_get_len(msg); mavlink_msg_data16_get_data(msg, data16->data); #else - memcpy(data16, _MAV_PAYLOAD(msg), 18); + memcpy(data16, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA16_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h index a9b3fe28d69977f9ac91fb155e02693cdb16f663..46c804a3c2eaab3ee9767e0a8640d6eb8a232023 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h @@ -12,6 +12,9 @@ typedef struct __mavlink_data32_t #define MAVLINK_MSG_ID_DATA32_LEN 34 #define MAVLINK_MSG_ID_170_LEN 34 +#define MAVLINK_MSG_ID_DATA32_CRC 73 +#define MAVLINK_MSG_ID_170_CRC 73 + #define MAVLINK_MSG_DATA32_FIELD_DATA_LEN 32 #define MAVLINK_MESSAGE_INFO_DATA32 { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_data32_pack(uint8_t system_id, uint8_t compon uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[34]; + char buf[MAVLINK_MSG_ID_DATA32_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN); #else mavlink_data32_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA32; - return mavlink_finalize_message(msg, system_id, component_id, 34, 73); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA32_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_data32_pack_chan(uint8_t system_id, uint8_t c uint8_t type,uint8_t len,const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[34]; + char buf[MAVLINK_MSG_ID_DATA32_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN); #else mavlink_data32_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA32; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 34, 73); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA32_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_data32_encode(uint8_t system_id, uint8_t comp static inline void mavlink_msg_data32_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[34]; + char buf[MAVLINK_MSG_ID_DATA32_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, 34, 73); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN); +#endif #else mavlink_data32_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, 34, 73); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, MAVLINK_MSG_ID_DATA32_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_data32_decode(const mavlink_message_t* msg, mavli data32->len = mavlink_msg_data32_get_len(msg); mavlink_msg_data32_get_data(msg, data32->data); #else - memcpy(data32, _MAV_PAYLOAD(msg), 34); + memcpy(data32, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA32_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h index 29dcaa6d807731f1fac2489c20efc6c599ce1a1d..843084dffa9540bd2b9ce48c97c82b2e92661469 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h @@ -12,6 +12,9 @@ typedef struct __mavlink_data64_t #define MAVLINK_MSG_ID_DATA64_LEN 66 #define MAVLINK_MSG_ID_171_LEN 66 +#define MAVLINK_MSG_ID_DATA64_CRC 181 +#define MAVLINK_MSG_ID_171_CRC 181 + #define MAVLINK_MSG_DATA64_FIELD_DATA_LEN 64 #define MAVLINK_MESSAGE_INFO_DATA64 { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_data64_pack(uint8_t system_id, uint8_t compon uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[66]; + char buf[MAVLINK_MSG_ID_DATA64_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 66); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN); #else mavlink_data64_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 66); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA64; - return mavlink_finalize_message(msg, system_id, component_id, 66, 181); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA64_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_data64_pack_chan(uint8_t system_id, uint8_t c uint8_t type,uint8_t len,const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[66]; + char buf[MAVLINK_MSG_ID_DATA64_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 66); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN); #else mavlink_data64_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 66); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA64; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 66, 181); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA64_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_data64_encode(uint8_t system_id, uint8_t comp static inline void mavlink_msg_data64_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[66]; + char buf[MAVLINK_MSG_ID_DATA64_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, 66, 181); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN); +#endif #else mavlink_data64_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, 66, 181); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, MAVLINK_MSG_ID_DATA64_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_data64_decode(const mavlink_message_t* msg, mavli data64->len = mavlink_msg_data64_get_len(msg); mavlink_msg_data64_get_data(msg, data64->data); #else - memcpy(data64, _MAV_PAYLOAD(msg), 66); + memcpy(data64, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA64_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h index df0821c878652d23f6aadc13fc0561ae8ae50d99..095628865cf551c80ce1383645a9344707563470 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h @@ -12,6 +12,9 @@ typedef struct __mavlink_data96_t #define MAVLINK_MSG_ID_DATA96_LEN 98 #define MAVLINK_MSG_ID_172_LEN 98 +#define MAVLINK_MSG_ID_DATA96_CRC 22 +#define MAVLINK_MSG_ID_172_CRC 22 + #define MAVLINK_MSG_DATA96_FIELD_DATA_LEN 96 #define MAVLINK_MESSAGE_INFO_DATA96 { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_data96_pack(uint8_t system_id, uint8_t compon uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[98]; + char buf[MAVLINK_MSG_ID_DATA96_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 98); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN); #else mavlink_data96_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 98); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA96; - return mavlink_finalize_message(msg, system_id, component_id, 98, 22); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA96_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_data96_pack_chan(uint8_t system_id, uint8_t c uint8_t type,uint8_t len,const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[98]; + char buf[MAVLINK_MSG_ID_DATA96_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 98); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN); #else mavlink_data96_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 98); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA96; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 98, 22); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA96_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_data96_encode(uint8_t system_id, uint8_t comp static inline void mavlink_msg_data96_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[98]; + char buf[MAVLINK_MSG_ID_DATA96_LEN]; _mav_put_uint8_t(buf, 0, type); _mav_put_uint8_t(buf, 1, len); _mav_put_uint8_t_array(buf, 2, data, 96); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, 98, 22); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN); +#endif #else mavlink_data96_t packet; packet.type = type; packet.len = len; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, 98, 22); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, MAVLINK_MSG_ID_DATA96_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_data96_decode(const mavlink_message_t* msg, mavli data96->len = mavlink_msg_data96_get_len(msg); mavlink_msg_data96_get_data(msg, data96->data); #else - memcpy(data96, _MAV_PAYLOAD(msg), 98); + memcpy(data96, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA96_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h index cc49c50255e67d10698335fc3bb14a2d7104e5b9..bcc706a887d8266c7f1187ea0b20581a421c8922 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h @@ -20,6 +20,9 @@ typedef struct __mavlink_digicam_configure_t #define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15 #define MAVLINK_MSG_ID_154_LEN 15 +#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC 84 +#define MAVLINK_MSG_ID_154_CRC 84 + #define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN]; _mav_put_float(buf, 0, extra_value); _mav_put_uint16_t(buf, 4, shutter_speed); _mav_put_uint8_t(buf, 6, target_system); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin _mav_put_uint8_t(buf, 13, engine_cut_off); _mav_put_uint8_t(buf, 14, extra_param); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); #else mavlink_digicam_configure_t packet; packet.extra_value = extra_value; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin packet.engine_cut_off = engine_cut_off; packet.extra_param = extra_param; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; - return mavlink_finalize_message(msg, system_id, component_id, 15, 84); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id uint8_t target_system,uint8_t target_component,uint8_t mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN]; _mav_put_float(buf, 0, extra_value); _mav_put_uint16_t(buf, 4, shutter_speed); _mav_put_uint8_t(buf, 6, target_system); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id _mav_put_uint8_t(buf, 13, engine_cut_off); _mav_put_uint8_t(buf, 14, extra_param); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); #else mavlink_digicam_configure_t packet; packet.extra_value = extra_value; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id packet.engine_cut_off = engine_cut_off; packet.extra_param = extra_param; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 84); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, u static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN]; _mav_put_float(buf, 0, extra_value); _mav_put_uint16_t(buf, 4, shutter_speed); _mav_put_uint8_t(buf, 6, target_system); @@ -204,7 +215,11 @@ static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, ui _mav_put_uint8_t(buf, 13, engine_cut_off); _mav_put_uint8_t(buf, 14, extra_param); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, 15, 84); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); +#endif #else mavlink_digicam_configure_t packet; packet.extra_value = extra_value; @@ -219,7 +234,11 @@ static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, ui packet.engine_cut_off = engine_cut_off; packet.extra_param = extra_param; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, 15, 84); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg); digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg); #else - memcpy(digicam_configure, _MAV_PAYLOAD(msg), 15); + memcpy(digicam_configure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h index a3b4878c434c3bee55a59ccc964b36f8d59f99ca..7fa8cdfef8696261eeb41dbbf30915c9b791fcf1 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h @@ -19,6 +19,9 @@ typedef struct __mavlink_digicam_control_t #define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13 #define MAVLINK_MSG_ID_155_LEN 13 +#define MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC 22 +#define MAVLINK_MSG_ID_155_CRC 22 + #define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \ @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8 uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[13]; + char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN]; _mav_put_float(buf, 0, extra_value); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 11, command_id); _mav_put_uint8_t(buf, 12, extra_param); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); #else mavlink_digicam_control_t packet; packet.extra_value = extra_value; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8 packet.command_id = command_id; packet.extra_param = extra_param; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 13, 22); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); +#endif } /** @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, uint8_t target_system,uint8_t target_component,uint8_t session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[13]; + char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN]; _mav_put_float(buf, 0, extra_value); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 11, command_id); _mav_put_uint8_t(buf, 12, extra_param); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); #else mavlink_digicam_control_t packet; packet.extra_value = extra_value; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, packet.command_id = command_id; packet.extra_param = extra_param; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 22); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); +#endif } /** @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uin static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[13]; + char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN]; _mav_put_float(buf, 0, extra_value); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); @@ -194,7 +205,11 @@ static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 11, command_id); _mav_put_uint8_t(buf, 12, extra_param); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, 13, 22); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); +#endif #else mavlink_digicam_control_t packet; packet.extra_value = extra_value; @@ -208,7 +223,11 @@ static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint packet.command_id = command_id; packet.extra_param = extra_param; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, 13, 22); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); +#endif #endif } @@ -337,6 +356,6 @@ static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* m digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg); digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg); #else - memcpy(digicam_control, _MAV_PAYLOAD(msg), 13); + memcpy(digicam_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h index c1e405b0a5a986bf54635eb15e21204880458f77..2cd4fc798ca9ca9fa3066bddfd451b1b649251f2 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h @@ -12,6 +12,9 @@ typedef struct __mavlink_fence_fetch_point_t #define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3 #define MAVLINK_MSG_ID_161_LEN 3 +#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC 68 +#define MAVLINK_MSG_ID_161_CRC 68 + #define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uin uint8_t target_system, uint8_t target_component, uint8_t idx) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, idx); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); #else mavlink_fence_fetch_point_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.idx = idx; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; - return mavlink_finalize_message(msg, system_id, component_id, 3, 68); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id uint8_t target_system,uint8_t target_component,uint8_t idx) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, idx); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); #else mavlink_fence_fetch_point_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.idx = idx; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 68); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, u static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, idx); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, 3, 68); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); +#endif #else mavlink_fence_fetch_point_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.idx = idx; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, 3, 68); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg); fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg); #else - memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), 3); + memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h index b31319c74909effcc71e3f2217ef8f04f5593bd6..b3c4706ee092b386d3aab5e20c0f484fada03a97 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h @@ -15,6 +15,9 @@ typedef struct __mavlink_fence_point_t #define MAVLINK_MSG_ID_FENCE_POINT_LEN 12 #define MAVLINK_MSG_ID_160_LEN 12 +#define MAVLINK_MSG_ID_FENCE_POINT_CRC 78 +#define MAVLINK_MSG_ID_160_CRC 78 + #define MAVLINK_MESSAGE_INFO_FENCE_POINT { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN]; _mav_put_float(buf, 0, lat); _mav_put_float(buf, 4, lng); _mav_put_uint8_t(buf, 8, target_system); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c _mav_put_uint8_t(buf, 10, idx); _mav_put_uint8_t(buf, 11, count); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); #else mavlink_fence_point_t packet; packet.lat = lat; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c packet.idx = idx; packet.count = count; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; - return mavlink_finalize_message(msg, system_id, component_id, 12, 78); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,float lat,float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN]; _mav_put_float(buf, 0, lat); _mav_put_float(buf, 4, lng); _mav_put_uint8_t(buf, 8, target_system); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint _mav_put_uint8_t(buf, 10, idx); _mav_put_uint8_t(buf, 11, count); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); #else mavlink_fence_point_t packet; packet.lat = lat; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint packet.idx = idx; packet.count = count; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 78); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN]; _mav_put_float(buf, 0, lat); _mav_put_float(buf, 4, lng); _mav_put_uint8_t(buf, 8, target_system); @@ -154,7 +165,11 @@ static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t _mav_put_uint8_t(buf, 10, idx); _mav_put_uint8_t(buf, 11, count); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, 12, 78); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); +#endif #else mavlink_fence_point_t packet; packet.lat = lat; @@ -164,7 +179,11 @@ static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t packet.idx = idx; packet.count = count; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, 12, 78); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, fence_point->idx = mavlink_msg_fence_point_get_idx(msg); fence_point->count = mavlink_msg_fence_point_get_count(msg); #else - memcpy(fence_point, _MAV_PAYLOAD(msg), 12); + memcpy(fence_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_POINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h index ce3e7ee67bb51e7884d30631eb1506328a0040df..32f2bc03a8b709c7afca90e0e2fba3cb0cc2fea1 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h @@ -13,6 +13,9 @@ typedef struct __mavlink_fence_status_t #define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8 #define MAVLINK_MSG_ID_162_LEN 8 +#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189 +#define MAVLINK_MSG_ID_162_CRC 189 + #define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; + char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; _mav_put_uint32_t(buf, 0, breach_time); _mav_put_uint16_t(buf, 4, breach_count); _mav_put_uint8_t(buf, 6, breach_status); _mav_put_uint8_t(buf, 7, breach_type); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); #else mavlink_fence_status_t packet; packet.breach_time = breach_time; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t packet.breach_status = breach_status; packet.breach_type = breach_type; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 8, 189); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; + char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; _mav_put_uint32_t(buf, 0, breach_time); _mav_put_uint16_t(buf, 4, breach_count); _mav_put_uint8_t(buf, 6, breach_status); _mav_put_uint8_t(buf, 7, breach_type); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); #else mavlink_fence_status_t packet; packet.breach_time = breach_time; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin packet.breach_status = breach_status; packet.breach_type = breach_type; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 189); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; + char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; _mav_put_uint32_t(buf, 0, breach_time); _mav_put_uint16_t(buf, 4, breach_count); _mav_put_uint8_t(buf, 6, breach_status); _mav_put_uint8_t(buf, 7, breach_type); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, 8, 189); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#endif #else mavlink_fence_status_t packet; packet.breach_time = breach_time; @@ -142,7 +157,11 @@ static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t packet.breach_status = breach_status; packet.breach_type = breach_type; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, 8, 189); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg); fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg); #else - memcpy(fence_status, _MAV_PAYLOAD(msg), 8); + memcpy(fence_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h index 952e65951be20ef7f2f4c3efde64251f672107b1..73870ec0fb7c1a38d06acfbefedb780fd4c3b44d 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h @@ -11,6 +11,9 @@ typedef struct __mavlink_hwstatus_t #define MAVLINK_MSG_ID_HWSTATUS_LEN 3 #define MAVLINK_MSG_ID_165_LEN 3 +#define MAVLINK_MSG_ID_HWSTATUS_CRC 21 +#define MAVLINK_MSG_ID_165_CRC 21 + #define MAVLINK_MESSAGE_INFO_HWSTATUS { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t comp uint16_t Vcc, uint8_t I2Cerr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_HWSTATUS_LEN]; _mav_put_uint16_t(buf, 0, Vcc); _mav_put_uint8_t(buf, 2, I2Cerr); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN); #else mavlink_hwstatus_t packet; packet.Vcc = Vcc; packet.I2Cerr = I2Cerr; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HWSTATUS; - return mavlink_finalize_message(msg, system_id, component_id, 3, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HWSTATUS_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t uint16_t Vcc,uint8_t I2Cerr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_HWSTATUS_LEN]; _mav_put_uint16_t(buf, 0, Vcc); _mav_put_uint8_t(buf, 2, I2Cerr); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN); #else mavlink_hwstatus_t packet; packet.Vcc = Vcc; packet.I2Cerr = I2Cerr; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HWSTATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HWSTATUS_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_HWSTATUS_LEN]; _mav_put_uint16_t(buf, 0, Vcc); _mav_put_uint8_t(buf, 2, I2Cerr); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, 3, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN); +#endif #else mavlink_hwstatus_t packet; packet.Vcc = Vcc; packet.I2Cerr = I2Cerr; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, 3, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, MAVLINK_MSG_ID_HWSTATUS_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mav hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg); hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg); #else - memcpy(hwstatus, _MAV_PAYLOAD(msg), 3); + memcpy(hwstatus, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HWSTATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h index 7caac1c5a1b8d634c4fb020b911443f509cfea32..f7b04fba71a8799ae8be1cd5c32570b0358f3905 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h @@ -18,6 +18,9 @@ typedef struct __mavlink_limits_status_t #define MAVLINK_MSG_ID_LIMITS_STATUS_LEN 22 #define MAVLINK_MSG_ID_167_LEN 22 +#define MAVLINK_MSG_ID_LIMITS_STATUS_CRC 144 +#define MAVLINK_MSG_ID_167_CRC 144 + #define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN]; _mav_put_uint32_t(buf, 0, last_trigger); _mav_put_uint32_t(buf, 4, last_action); _mav_put_uint32_t(buf, 8, last_recovery); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 20, mods_required); _mav_put_uint8_t(buf, 21, mods_triggered); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); #else mavlink_limits_status_t packet; packet.last_trigger = last_trigger; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t packet.mods_required = mods_required; packet.mods_triggered = mods_triggered; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 22, 144); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, ui uint8_t limits_state,uint32_t last_trigger,uint32_t last_action,uint32_t last_recovery,uint32_t last_clear,uint16_t breach_count,uint8_t mods_enabled,uint8_t mods_required,uint8_t mods_triggered) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN]; _mav_put_uint32_t(buf, 0, last_trigger); _mav_put_uint32_t(buf, 4, last_action); _mav_put_uint32_t(buf, 8, last_recovery); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, ui _mav_put_uint8_t(buf, 20, mods_required); _mav_put_uint8_t(buf, 21, mods_triggered); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); #else mavlink_limits_status_t packet; packet.last_trigger = last_trigger; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, ui packet.mods_required = mods_required; packet.mods_triggered = mods_triggered; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 144); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8 static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN]; _mav_put_uint32_t(buf, 0, last_trigger); _mav_put_uint32_t(buf, 4, last_action); _mav_put_uint32_t(buf, 8, last_recovery); @@ -184,7 +195,11 @@ static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_ _mav_put_uint8_t(buf, 20, mods_required); _mav_put_uint8_t(buf, 21, mods_triggered); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, 22, 144); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); +#endif #else mavlink_limits_status_t packet; packet.last_trigger = last_trigger; @@ -197,7 +212,11 @@ static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_ packet.mods_required = mods_required; packet.mods_triggered = mods_triggered; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, 22, 144); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_limits_status_decode(const mavlink_message_t* msg limits_status->mods_required = mavlink_msg_limits_status_get_mods_required(msg); limits_status->mods_triggered = mavlink_msg_limits_status_get_mods_triggered(msg); #else - memcpy(limits_status, _MAV_PAYLOAD(msg), 22); + memcpy(limits_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LIMITS_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h index a095a804f3cb5a6a59569f934b0a6d0a4c30f81a..437029eed7732f3ad5e7b62436cbfa408e6d0684 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h @@ -11,6 +11,9 @@ typedef struct __mavlink_meminfo_t #define MAVLINK_MSG_ID_MEMINFO_LEN 4 #define MAVLINK_MSG_ID_152_LEN 4 +#define MAVLINK_MSG_ID_MEMINFO_CRC 208 +#define MAVLINK_MSG_ID_152_CRC 208 + #define MAVLINK_MESSAGE_INFO_MEMINFO { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t compo uint16_t brkval, uint16_t freemem) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MEMINFO_LEN]; _mav_put_uint16_t(buf, 0, brkval); _mav_put_uint16_t(buf, 2, freemem); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN); #else mavlink_meminfo_t packet; packet.brkval = brkval; packet.freemem = freemem; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MEMINFO; - return mavlink_finalize_message(msg, system_id, component_id, 4, 208); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMINFO_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t uint16_t brkval,uint16_t freemem) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MEMINFO_LEN]; _mav_put_uint16_t(buf, 0, brkval); _mav_put_uint16_t(buf, 2, freemem); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN); #else mavlink_meminfo_t packet; packet.brkval = brkval; packet.freemem = freemem; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MEMINFO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMINFO_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MEMINFO_LEN]; _mav_put_uint16_t(buf, 0, brkval); _mav_put_uint16_t(buf, 2, freemem); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, 4, 208); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN); +#endif #else mavlink_meminfo_t packet; packet.brkval = brkval; packet.freemem = freemem; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, 4, 208); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, MAVLINK_MSG_ID_MEMINFO_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavl meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg); meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg); #else - memcpy(meminfo, _MAV_PAYLOAD(msg), 4); + memcpy(meminfo, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMINFO_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h index 051a7183794528cedbc1c29984c3d47dd15b4b8e..450153c6fe5bd2ab74f3f7be69b55a9a71671737 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h @@ -15,6 +15,9 @@ typedef struct __mavlink_mount_configure_t #define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6 #define MAVLINK_MSG_ID_156_LEN 6 +#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC 19 +#define MAVLINK_MSG_ID_156_CRC 19 + #define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8 uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, mount_mode); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 4, stab_pitch); _mav_put_uint8_t(buf, 5, stab_yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); #else mavlink_mount_configure_t packet; packet.target_system = target_system; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8 packet.stab_pitch = stab_pitch; packet.stab_yaw = stab_yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; - return mavlink_finalize_message(msg, system_id, component_id, 6, 19); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, uint8_t target_system,uint8_t target_component,uint8_t mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, mount_mode); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 4, stab_pitch); _mav_put_uint8_t(buf, 5, stab_yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); #else mavlink_mount_configure_t packet; packet.target_system = target_system; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, packet.stab_pitch = stab_pitch; packet.stab_yaw = stab_yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 19); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uin static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, mount_mode); @@ -154,7 +165,11 @@ static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 4, stab_pitch); _mav_put_uint8_t(buf, 5, stab_yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, 6, 19); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); +#endif #else mavlink_mount_configure_t packet; packet.target_system = target_system; @@ -164,7 +179,11 @@ static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint packet.stab_pitch = stab_pitch; packet.stab_yaw = stab_yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, 6, 19); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* m mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg); mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg); #else - memcpy(mount_configure, _MAV_PAYLOAD(msg), 6); + memcpy(mount_configure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h index a519922997ce10af1eff72308e9423b85749cb51..5b83d7e970da56f5c12f3951be0d7ef9bf15638b 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h @@ -15,6 +15,9 @@ typedef struct __mavlink_mount_control_t #define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15 #define MAVLINK_MSG_ID_157_LEN 15 +#define MAVLINK_MSG_ID_MOUNT_CONTROL_CRC 21 +#define MAVLINK_MSG_ID_157_CRC 21 + #define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN]; _mav_put_int32_t(buf, 0, input_a); _mav_put_int32_t(buf, 4, input_b); _mav_put_int32_t(buf, 8, input_c); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 13, target_component); _mav_put_uint8_t(buf, 14, save_position); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); #else mavlink_mount_control_t packet; packet.input_a = input_a; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t packet.target_component = target_component; packet.save_position = save_position; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 15, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui uint8_t target_system,uint8_t target_component,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN]; _mav_put_int32_t(buf, 0, input_a); _mav_put_int32_t(buf, 4, input_b); _mav_put_int32_t(buf, 8, input_c); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui _mav_put_uint8_t(buf, 13, target_component); _mav_put_uint8_t(buf, 14, save_position); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); #else mavlink_mount_control_t packet; packet.input_a = input_a; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui packet.target_component = target_component; packet.save_position = save_position; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8 static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN]; _mav_put_int32_t(buf, 0, input_a); _mav_put_int32_t(buf, 4, input_b); _mav_put_int32_t(buf, 8, input_c); @@ -154,7 +165,11 @@ static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_ _mav_put_uint8_t(buf, 13, target_component); _mav_put_uint8_t(buf, 14, save_position); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, 15, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); +#endif #else mavlink_mount_control_t packet; packet.input_a = input_a; @@ -164,7 +179,11 @@ static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_ packet.target_component = target_component; packet.save_position = save_position; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, 15, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg); mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg); #else - memcpy(mount_control, _MAV_PAYLOAD(msg), 15); + memcpy(mount_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h index edc188ebd49b7c2f90dfade166c557b1d091cd28..c031db42b43fa630d0a2eef8835c2e2233a8291e 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h @@ -14,6 +14,9 @@ typedef struct __mavlink_mount_status_t #define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14 #define MAVLINK_MSG_ID_158_LEN 14 +#define MAVLINK_MSG_ID_MOUNT_STATUS_CRC 134 +#define MAVLINK_MSG_ID_158_CRC 134 + #define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN]; _mav_put_int32_t(buf, 0, pointing_a); _mav_put_int32_t(buf, 4, pointing_b); _mav_put_int32_t(buf, 8, pointing_c); _mav_put_uint8_t(buf, 12, target_system); _mav_put_uint8_t(buf, 13, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); #else mavlink_mount_status_t packet; packet.pointing_a = pointing_a; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 14, 134); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin uint8_t target_system,uint8_t target_component,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN]; _mav_put_int32_t(buf, 0, pointing_a); _mav_put_int32_t(buf, 4, pointing_b); _mav_put_int32_t(buf, 8, pointing_c); _mav_put_uint8_t(buf, 12, target_system); _mav_put_uint8_t(buf, 13, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); #else mavlink_mount_status_t packet; packet.pointing_a = pointing_a; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 134); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN]; _mav_put_int32_t(buf, 0, pointing_a); _mav_put_int32_t(buf, 4, pointing_b); _mav_put_int32_t(buf, 8, pointing_c); _mav_put_uint8_t(buf, 12, target_system); _mav_put_uint8_t(buf, 13, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, 14, 134); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); +#endif #else mavlink_mount_status_t packet; packet.pointing_a = pointing_a; @@ -153,7 +168,11 @@ static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, 14, 134); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg); mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg); #else - memcpy(mount_status, _MAV_PAYLOAD(msg), 14); + memcpy(mount_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MOUNT_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h index 0f3d03c0a64a8f08711f8a9dfc1d9976c05d9804..e13776993e4a51472549ded94b0355261a47b46d 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h @@ -16,6 +16,9 @@ typedef struct __mavlink_radio_t #define MAVLINK_MSG_ID_RADIO_LEN 9 #define MAVLINK_MSG_ID_166_LEN 9 +#define MAVLINK_MSG_ID_RADIO_CRC 21 +#define MAVLINK_MSG_ID_166_CRC 21 + #define MAVLINK_MESSAGE_INFO_RADIO { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_RADIO_LEN]; _mav_put_uint16_t(buf, 0, rxerrors); _mav_put_uint16_t(buf, 2, fixed); _mav_put_uint8_t(buf, 4, rssi); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone _mav_put_uint8_t(buf, 7, noise); _mav_put_uint8_t(buf, 8, remnoise); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN); #else mavlink_radio_t packet; packet.rxerrors = rxerrors; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone packet.noise = noise; packet.remnoise = remnoise; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RADIO; - return mavlink_finalize_message(msg, system_id, component_id, 9, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_RADIO_LEN]; _mav_put_uint16_t(buf, 0, rxerrors); _mav_put_uint16_t(buf, 2, fixed); _mav_put_uint8_t(buf, 4, rssi); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co _mav_put_uint8_t(buf, 7, noise); _mav_put_uint8_t(buf, 8, remnoise); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN); #else mavlink_radio_t packet; packet.rxerrors = rxerrors; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co packet.noise = noise; packet.remnoise = remnoise; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RADIO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_RADIO_LEN]; _mav_put_uint16_t(buf, 0, rxerrors); _mav_put_uint16_t(buf, 2, fixed); _mav_put_uint8_t(buf, 4, rssi); @@ -164,7 +175,11 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, _mav_put_uint8_t(buf, 7, noise); _mav_put_uint8_t(buf, 8, remnoise); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN); +#endif #else mavlink_radio_t packet; packet.rxerrors = rxerrors; @@ -175,7 +190,11 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, packet.noise = noise; packet.remnoise = remnoise; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, MAVLINK_MSG_ID_RADIO_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin radio->noise = mavlink_msg_radio_get_noise(msg); radio->remnoise = mavlink_msg_radio_get_remnoise(msg); #else - memcpy(radio, _MAV_PAYLOAD(msg), 9); + memcpy(radio, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h new file mode 100644 index 0000000000000000000000000000000000000000..d88abe36a424d180be2e692e18d516422f93057b --- /dev/null +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h @@ -0,0 +1,185 @@ +// MESSAGE RANGEFINDER PACKING + +#define MAVLINK_MSG_ID_RANGEFINDER 173 + +typedef struct __mavlink_rangefinder_t +{ + float distance; ///< distance in meters + float voltage; ///< raw voltage if available, zero otherwise +} mavlink_rangefinder_t; + +#define MAVLINK_MSG_ID_RANGEFINDER_LEN 8 +#define MAVLINK_MSG_ID_173_LEN 8 + +#define MAVLINK_MSG_ID_RANGEFINDER_CRC 83 +#define MAVLINK_MSG_ID_173_CRC 83 + + + +#define MAVLINK_MESSAGE_INFO_RANGEFINDER { \ + "RANGEFINDER", \ + 2, \ + { { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rangefinder_t, distance) }, \ + { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rangefinder_t, voltage) }, \ + } \ +} + + +/** + * @brief Pack a rangefinder 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 distance distance in meters + * @param voltage raw voltage if available, zero otherwise + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rangefinder_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float distance, float voltage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN]; + _mav_put_float(buf, 0, distance); + _mav_put_float(buf, 4, voltage); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#else + mavlink_rangefinder_t packet; + packet.distance = distance; + packet.voltage = voltage; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RANGEFINDER; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif +} + +/** + * @brief Pack a rangefinder message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param distance distance in meters + * @param voltage raw voltage if available, zero otherwise + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rangefinder_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float distance,float voltage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN]; + _mav_put_float(buf, 0, distance); + _mav_put_float(buf, 4, voltage); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#else + mavlink_rangefinder_t packet; + packet.distance = distance; + packet.voltage = voltage; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RANGEFINDER; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif +} + +/** + * @brief Encode a rangefinder 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 rangefinder C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rangefinder_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder) +{ + return mavlink_msg_rangefinder_pack(system_id, component_id, msg, rangefinder->distance, rangefinder->voltage); +} + +/** + * @brief Send a rangefinder message + * @param chan MAVLink channel to send the message + * + * @param distance distance in meters + * @param voltage raw voltage if available, zero otherwise + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rangefinder_send(mavlink_channel_t chan, float distance, float voltage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN]; + _mav_put_float(buf, 0, distance); + _mav_put_float(buf, 4, voltage); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif +#else + mavlink_rangefinder_t packet; + packet.distance = distance; + packet.voltage = voltage; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)&packet, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)&packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif +#endif +} + +#endif + +// MESSAGE RANGEFINDER UNPACKING + + +/** + * @brief Get field distance from rangefinder message + * + * @return distance in meters + */ +static inline float mavlink_msg_rangefinder_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field voltage from rangefinder message + * + * @return raw voltage if available, zero otherwise + */ +static inline float mavlink_msg_rangefinder_get_voltage(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a rangefinder message into a struct + * + * @param msg The message to decode + * @param rangefinder C-struct to decode the message contents into + */ +static inline void mavlink_msg_rangefinder_decode(const mavlink_message_t* msg, mavlink_rangefinder_t* rangefinder) +{ +#if MAVLINK_NEED_BYTE_SWAP + rangefinder->distance = mavlink_msg_rangefinder_get_distance(msg); + rangefinder->voltage = mavlink_msg_rangefinder_get_voltage(msg); +#else + memcpy(rangefinder, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RANGEFINDER_LEN); +#endif +} diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h index 56fb52d96d2720be8a54932427a559287873edec..d121e48e6670b1340cc52fc1fae1352e77e2aadb 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h @@ -21,6 +21,9 @@ typedef struct __mavlink_sensor_offsets_t #define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42 #define MAVLINK_MSG_ID_150_LEN 42 +#define MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC 134 +#define MAVLINK_MSG_ID_150_CRC 134 + #define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \ @@ -66,7 +69,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_ int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[42]; + char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN]; _mav_put_float(buf, 0, mag_declination); _mav_put_int32_t(buf, 4, raw_press); _mav_put_int32_t(buf, 8, raw_temp); @@ -80,7 +83,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_ _mav_put_int16_t(buf, 38, mag_ofs_y); _mav_put_int16_t(buf, 40, mag_ofs_z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); #else mavlink_sensor_offsets_t packet; packet.mag_declination = mag_declination; @@ -96,11 +99,15 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_ packet.mag_ofs_y = mag_ofs_y; packet.mag_ofs_z = mag_ofs_z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; - return mavlink_finalize_message(msg, system_id, component_id, 42, 134); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); +#endif } /** @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[42]; + char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN]; _mav_put_float(buf, 0, mag_declination); _mav_put_int32_t(buf, 4, raw_press); _mav_put_int32_t(buf, 8, raw_temp); @@ -142,7 +149,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u _mav_put_int16_t(buf, 38, mag_ofs_y); _mav_put_int16_t(buf, 40, mag_ofs_z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); #else mavlink_sensor_offsets_t packet; packet.mag_declination = mag_declination; @@ -158,11 +165,15 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u packet.mag_ofs_y = mag_ofs_y; packet.mag_ofs_z = mag_ofs_z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 134); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); +#endif } /** @@ -200,7 +211,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[42]; + char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN]; _mav_put_float(buf, 0, mag_declination); _mav_put_int32_t(buf, 4, raw_press); _mav_put_int32_t(buf, 8, raw_temp); @@ -214,7 +225,11 @@ static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16 _mav_put_int16_t(buf, 38, mag_ofs_y); _mav_put_int16_t(buf, 40, mag_ofs_z); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, 42, 134); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); +#endif #else mavlink_sensor_offsets_t packet; packet.mag_declination = mag_declination; @@ -230,7 +245,11 @@ static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16 packet.mag_ofs_y = mag_ofs_y; packet.mag_ofs_z = mag_ofs_z; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, 42, 134); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); +#endif #endif } @@ -381,6 +400,6 @@ static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* ms sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg); sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg); #else - memcpy(sensor_offsets, _MAV_PAYLOAD(msg), 42); + memcpy(sensor_offsets, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h index 4c13fd1863d3db61a9e625bd7a70cc53867ef4d6..a59e9064947c211656afb510455a2329166fbaf7 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h @@ -14,6 +14,9 @@ typedef struct __mavlink_set_mag_offsets_t #define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8 #define MAVLINK_MSG_ID_151_LEN 8 +#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC 219 +#define MAVLINK_MSG_ID_151_CRC 219 + #define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8 uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; + char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN]; _mav_put_int16_t(buf, 0, mag_ofs_x); _mav_put_int16_t(buf, 2, mag_ofs_y); _mav_put_int16_t(buf, 4, mag_ofs_z); _mav_put_uint8_t(buf, 6, target_system); _mav_put_uint8_t(buf, 7, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); #else mavlink_set_mag_offsets_t packet; packet.mag_ofs_x = mag_ofs_x; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8 packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; - return mavlink_finalize_message(msg, system_id, component_id, 8, 219); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; + char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN]; _mav_put_int16_t(buf, 0, mag_ofs_x); _mav_put_int16_t(buf, 2, mag_ofs_y); _mav_put_int16_t(buf, 4, mag_ofs_z); _mav_put_uint8_t(buf, 6, target_system); _mav_put_uint8_t(buf, 7, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); #else mavlink_set_mag_offsets_t packet; packet.mag_ofs_x = mag_ofs_x; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 219); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uin static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; + char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN]; _mav_put_int16_t(buf, 0, mag_ofs_x); _mav_put_int16_t(buf, 2, mag_ofs_y); _mav_put_int16_t(buf, 4, mag_ofs_z); _mav_put_uint8_t(buf, 6, target_system); _mav_put_uint8_t(buf, 7, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 8, 219); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); +#endif #else mavlink_set_mag_offsets_t packet; packet.mag_ofs_x = mag_ofs_x; @@ -153,7 +168,11 @@ static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, 8, 219); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* m set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg); set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg); #else - memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8); + memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h index 8ee447c778f4d05ce6510f489e67bb302f0c3720..7373c8bffedb0a16cdf1d4f84224c97d00134d93 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h @@ -20,6 +20,9 @@ typedef struct __mavlink_simstate_t #define MAVLINK_MSG_ID_SIMSTATE_LEN 44 #define MAVLINK_MSG_ID_164_LEN 44 +#define MAVLINK_MSG_ID_SIMSTATE_CRC 111 +#define MAVLINK_MSG_ID_164_CRC 111 + #define MAVLINK_MESSAGE_INFO_SIMSTATE { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[44]; + char buf[MAVLINK_MSG_ID_SIMSTATE_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 36, lat); _mav_put_float(buf, 40, lng); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 44); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN); #else mavlink_simstate_t packet; packet.roll = roll; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp packet.lat = lat; packet.lng = lng; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 44); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SIMSTATE; - return mavlink_finalize_message(msg, system_id, component_id, 44, 111); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIMSTATE_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[44]; + char buf[MAVLINK_MSG_ID_SIMSTATE_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 36, lat); _mav_put_float(buf, 40, lng); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 44); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN); #else mavlink_simstate_t packet; packet.roll = roll; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t packet.lat = lat; packet.lng = lng; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 44); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SIMSTATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 44, 111); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIMSTATE_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[44]; + char buf[MAVLINK_MSG_ID_SIMSTATE_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -204,7 +215,11 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, _mav_put_float(buf, 36, lat); _mav_put_float(buf, 40, lng); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 44, 111); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN); +#endif #else mavlink_simstate_t packet; packet.roll = roll; @@ -219,7 +234,11 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, packet.lat = lat; packet.lng = lng; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 44, 111); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, MAVLINK_MSG_ID_SIMSTATE_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mav simstate->lat = mavlink_msg_simstate_get_lat(msg); simstate->lng = mavlink_msg_simstate_get_lng(msg); #else - memcpy(simstate, _MAV_PAYLOAD(msg), 44); + memcpy(simstate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIMSTATE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h index e7fa7d1eaaafeb6113035d2ee926f3668f94c953..ebdd2949d9e33a5713f2216d23c2005c3e93b53b 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h @@ -12,6 +12,9 @@ typedef struct __mavlink_wind_t #define MAVLINK_MSG_ID_WIND_LEN 12 #define MAVLINK_MSG_ID_168_LEN 12 +#define MAVLINK_MSG_ID_WIND_CRC 1 +#define MAVLINK_MSG_ID_168_CRC 1 + #define MAVLINK_MESSAGE_INFO_WIND { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t componen float direction, float speed, float speed_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_WIND_LEN]; _mav_put_float(buf, 0, direction); _mav_put_float(buf, 4, speed); _mav_put_float(buf, 8, speed_z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN); #else mavlink_wind_t packet; packet.direction = direction; packet.speed = speed; packet.speed_z = speed_z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WIND; - return mavlink_finalize_message(msg, system_id, component_id, 12, 1); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t com float direction,float speed,float speed_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_WIND_LEN]; _mav_put_float(buf, 0, direction); _mav_put_float(buf, 4, speed); _mav_put_float(buf, 8, speed_z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN); #else mavlink_wind_t packet; packet.direction = direction; packet.speed = speed; packet.speed_z = speed_z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WIND; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 1); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t compon static inline void mavlink_msg_wind_send(mavlink_channel_t chan, float direction, float speed, float speed_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_WIND_LEN]; _mav_put_float(buf, 0, direction); _mav_put_float(buf, 4, speed); _mav_put_float(buf, 8, speed_z); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, 12, 1); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN); +#endif #else mavlink_wind_t packet; packet.direction = direction; packet.speed = speed; packet.speed_z = speed_z; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, 12, 1); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, MAVLINK_MSG_ID_WIND_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_wind_decode(const mavlink_message_t* msg, mavlink wind->speed = mavlink_msg_wind_get_speed(msg); wind->speed_z = mavlink_msg_wind_get_speed_z(msg); #else - memcpy(wind, _MAV_PAYLOAD(msg), 12); + memcpy(wind, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WIND_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h index 0442ab787596f73ee2dc0e215761939348c465b0..07bf19ee07ed26db798a03512dae6a7e03066b2d 100644 --- a/libs/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h +++ b/libs/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h @@ -1180,6 +1180,51 @@ static void mavlink_test_data96(uint8_t system_id, uint8_t component_id, mavlink MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_rangefinder(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_rangefinder_t packet_in = { + 17.0, + 45.0, + }; + mavlink_rangefinder_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.distance = packet_in.distance; + packet1.voltage = packet_in.voltage; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_rangefinder_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_rangefinder_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_rangefinder_pack(system_id, component_id, &msg , packet1.distance , packet1.voltage ); + mavlink_msg_rangefinder_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_rangefinder_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.distance , packet1.voltage ); + mavlink_msg_rangefinder_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| 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)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_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 system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_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| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_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_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_ENUM_END=401, /* | */ -}; -#endif - /** @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. */ @@ -485,6 +445,9 @@ enum MAV_SEVERITY #include "./mavlink_msg_vicon_position_estimate.h" #include "./mavlink_msg_highres_imu.h" #include "./mavlink_msg_omnidirectional_flow.h" +#include "./mavlink_msg_hil_sensor.h" +#include "./mavlink_msg_sim_state.h" +#include "./mavlink_msg_radio_status.h" #include "./mavlink_msg_file_transfer_start.h" #include "./mavlink_msg_file_transfer_dir_list.h" #include "./mavlink_msg_file_transfer_res.h" diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h index 6db0592f248d9c899dea6b485feeb36c3c7a80f6..0ba416ee1481ad88814fe6d3a138699643fc4c85 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h @@ -16,6 +16,9 @@ typedef struct __mavlink_attitude_t #define MAVLINK_MSG_ID_ATTITUDE_LEN 28 #define MAVLINK_MSG_ID_30_LEN 28 +#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 +#define MAVLINK_MSG_ID_30_CRC 39 + #define MAVLINK_MESSAGE_INFO_ATTITUDE { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 20, pitchspeed); _mav_put_float(buf, 24, yawspeed); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); #else mavlink_attitude_t packet; packet.time_boot_ms = time_boot_ms; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, 28, 39); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 20, pitchspeed); _mav_put_float(buf, 24, yawspeed); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); #else mavlink_attitude_t packet; packet.time_boot_ms = time_boot_ms; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 39); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); @@ -164,7 +175,11 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t ti _mav_put_float(buf, 20, pitchspeed); _mav_put_float(buf, 24, yawspeed); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, 28, 39); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif #else mavlink_attitude_t packet; packet.time_boot_ms = time_boot_ms; @@ -175,7 +190,11 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t ti packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, 28, 39); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mav attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); #else - memcpy(attitude, _MAV_PAYLOAD(msg), 28); + memcpy(attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h index 556048865510de531bcac997826e7a033d5f77f2..611803f2b74e01e2dfcee637d4cf1da803dbc05f 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h @@ -17,6 +17,9 @@ typedef struct __mavlink_attitude_quaternion_t #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 #define MAVLINK_MSG_ID_31_LEN 32 +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 +#define MAVLINK_MSG_ID_31_CRC 246 + #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ @@ -54,7 +57,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, q1); _mav_put_float(buf, 8, q2); @@ -64,7 +67,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u _mav_put_float(buf, 24, pitchspeed); _mav_put_float(buf, 28, yawspeed); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); #else mavlink_attitude_quaternion_t packet; packet.time_boot_ms = time_boot_ms; @@ -76,11 +79,15 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; - return mavlink_finalize_message(msg, system_id, component_id, 32, 246); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif } /** @@ -104,7 +111,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_ uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, q1); _mav_put_float(buf, 8, q2); @@ -114,7 +121,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_ _mav_put_float(buf, 24, pitchspeed); _mav_put_float(buf, 28, yawspeed); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); #else mavlink_attitude_quaternion_t packet; packet.time_boot_ms = time_boot_ms; @@ -126,11 +133,15 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_ packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 246); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif } /** @@ -164,7 +175,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, q1); _mav_put_float(buf, 8, q2); @@ -174,7 +185,11 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, _mav_put_float(buf, 24, pitchspeed); _mav_put_float(buf, 28, yawspeed); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, 32, 246); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif #else mavlink_attitude_quaternion_t packet; packet.time_boot_ms = time_boot_ms; @@ -186,7 +201,11 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, 32, 246); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif #endif } @@ -293,6 +312,6 @@ static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_ attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); #else - memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), 32); + memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h index baa119fde1a17f020e2955eebf65dfcc5ab97ba9..030b564c97e258c24a1056374552a1720d1291e0 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h @@ -10,6 +10,9 @@ typedef struct __mavlink_auth_key_t #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 #define MAVLINK_MSG_ID_7_LEN 32 +#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 +#define MAVLINK_MSG_ID_7_CRC 119 + #define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ @@ -33,19 +36,23 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp const char *key) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); #else mavlink_auth_key_t packet; mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; - return mavlink_finalize_message(msg, system_id, component_id, 32, 119); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif } /** @@ -62,19 +69,23 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t const char *key) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); #else mavlink_auth_key_t packet; mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif } /** @@ -101,15 +112,23 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; _mav_put_char_array(buf, 0, key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, 32, 119); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif #else mavlink_auth_key_t packet; mav_array_memcpy(packet.key, key, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, 32, 119); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif #endif } @@ -139,6 +158,6 @@ static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mav #if MAVLINK_NEED_BYTE_SWAP mavlink_msg_auth_key_get_key(msg, auth_key->key); #else - memcpy(auth_key, _MAV_PAYLOAD(msg), 32); + memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h index c78fb4f31fc8c26e1878150dbd67523e02859e4c..83c81598416e960692da02cd94a0fc0b558d9248 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h @@ -18,6 +18,9 @@ typedef struct __mavlink_battery_status_t #define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 16 #define MAVLINK_MSG_ID_147_LEN 16 +#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 42 +#define MAVLINK_MSG_ID_147_CRC 42 + #define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_ uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int8_t battery_remaining) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; _mav_put_uint16_t(buf, 0, voltage_cell_1); _mav_put_uint16_t(buf, 2, voltage_cell_2); _mav_put_uint16_t(buf, 4, voltage_cell_3); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 14, accu_id); _mav_put_int8_t(buf, 15, battery_remaining); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); #else mavlink_battery_status_t packet; packet.voltage_cell_1 = voltage_cell_1; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_ packet.accu_id = accu_id; packet.battery_remaining = battery_remaining; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 16, 42); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u uint8_t accu_id,uint16_t voltage_cell_1,uint16_t voltage_cell_2,uint16_t voltage_cell_3,uint16_t voltage_cell_4,uint16_t voltage_cell_5,uint16_t voltage_cell_6,int16_t current_battery,int8_t battery_remaining) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; _mav_put_uint16_t(buf, 0, voltage_cell_1); _mav_put_uint16_t(buf, 2, voltage_cell_2); _mav_put_uint16_t(buf, 4, voltage_cell_3); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u _mav_put_uint8_t(buf, 14, accu_id); _mav_put_int8_t(buf, 15, battery_remaining); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); #else mavlink_battery_status_t packet; packet.voltage_cell_1 = voltage_cell_1; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u packet.accu_id = accu_id; packet.battery_remaining = battery_remaining; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 42); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int8_t battery_remaining) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; _mav_put_uint16_t(buf, 0, voltage_cell_1); _mav_put_uint16_t(buf, 2, voltage_cell_2); _mav_put_uint16_t(buf, 4, voltage_cell_3); @@ -184,7 +195,11 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8 _mav_put_uint8_t(buf, 14, accu_id); _mav_put_int8_t(buf, 15, battery_remaining); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, 16, 42); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif #else mavlink_battery_status_t packet; packet.voltage_cell_1 = voltage_cell_1; @@ -197,7 +212,11 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8 packet.accu_id = accu_id; packet.battery_remaining = battery_remaining; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, 16, 42); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* ms battery_status->accu_id = mavlink_msg_battery_status_get_accu_id(msg); battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); #else - memcpy(battery_status, _MAV_PAYLOAD(msg), 16); + memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h index a558510084590c26fd6bbd3848686aff36fa44c2..c7195dfcaa0bf948fa771896f8acc0ef92488154 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h @@ -13,6 +13,9 @@ typedef struct __mavlink_change_operator_control_t #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 #define MAVLINK_MSG_ID_5_LEN 28 +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 +#define MAVLINK_MSG_ID_5_CRC 217 + #define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 #define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ @@ -42,23 +45,27 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, version); _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); #else mavlink_change_operator_control_t packet; packet.target_system = target_system; packet.control_request = control_request; packet.version = version; mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 28, 217); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif } /** @@ -78,23 +85,27 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, version); _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); #else mavlink_change_operator_control_t packet; packet.target_system = target_system; packet.control_request = control_request; packet.version = version; mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 217); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif } /** @@ -124,19 +135,27 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, version); _mav_put_char_array(buf, 3, passkey, 25); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28, 217); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif #else mavlink_change_operator_control_t packet; packet.target_system = target_system; packet.control_request = control_request; packet.version = version; mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28, 217); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif #endif } @@ -199,6 +218,6 @@ static inline void mavlink_msg_change_operator_control_decode(const mavlink_mess change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); #else - memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28); + memcpy(change_operator_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h index 1d89a0f787536d049c6fc19e827a34928965878b..5cf98e77fe5b5a8e38ffae28e47b0e71a150e956 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h @@ -12,6 +12,9 @@ typedef struct __mavlink_change_operator_control_ack_t #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 #define MAVLINK_MSG_ID_6_LEN 3 +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 +#define MAVLINK_MSG_ID_6_CRC 104 + #define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t syst uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; _mav_put_uint8_t(buf, 0, gcs_system_id); _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, ack); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); #else mavlink_change_operator_control_ack_t packet; packet.gcs_system_id = gcs_system_id; packet.control_request = control_request; packet.ack = ack; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 3, 104); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; _mav_put_uint8_t(buf, 0, gcs_system_id); _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, ack); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); #else mavlink_change_operator_control_ack_t packet; packet.gcs_system_id = gcs_system_id; packet.control_request = control_request; packet.ack = ack; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; _mav_put_uint8_t(buf, 0, gcs_system_id); _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, ack); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, 3, 104); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif #else mavlink_change_operator_control_ack_t packet; packet.gcs_system_id = gcs_system_id; packet.control_request = control_request; packet.ack = ack; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, 3, 104); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_ change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); #else - memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), 3); + memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h index df6e9b9e3b7ec998a2b2dbc37c7de695648eab01..82c2835de0cb15f536b8a6662f1c7995ebecfd7e 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h @@ -11,6 +11,9 @@ typedef struct __mavlink_command_ack_t #define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 #define MAVLINK_MSG_ID_77_LEN 3 +#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 +#define MAVLINK_MSG_ID_77_CRC 143 + #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c uint16_t command, uint8_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; _mav_put_uint16_t(buf, 0, command); _mav_put_uint8_t(buf, 2, result); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); #else mavlink_command_ack_t packet; packet.command = command; packet.result = result; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 3, 143); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint uint16_t command,uint8_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; _mav_put_uint16_t(buf, 0, command); _mav_put_uint8_t(buf, 2, result); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); #else mavlink_command_ack_t packet; packet.command = command; packet.result = result; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 143); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; _mav_put_uint16_t(buf, 0, command); _mav_put_uint8_t(buf, 2, result); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 3, 143); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif #else mavlink_command_ack_t packet; packet.command = command; packet.result = result; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 3, 143); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, command_ack->command = mavlink_msg_command_ack_get_command(msg); command_ack->result = mavlink_msg_command_ack_get_result(msg); #else - memcpy(command_ack, _MAV_PAYLOAD(msg), 3); + memcpy(command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h index 54ca77eaa2e5585d2f43d455a908ef15d56b370b..5c44c62844a52d5634b9645cb46e55ed3dc75e69 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h @@ -20,6 +20,9 @@ typedef struct __mavlink_command_long_t #define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 #define MAVLINK_MSG_ID_76_LEN 33 +#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 +#define MAVLINK_MSG_ID_76_CRC 152 + #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; _mav_put_float(buf, 0, param1); _mav_put_float(buf, 4, param2); _mav_put_float(buf, 8, param3); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 31, target_component); _mav_put_uint8_t(buf, 32, confirmation); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); #else mavlink_command_long_t packet; packet.param1 = param1; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t packet.target_component = target_component; packet.confirmation = confirmation; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; - return mavlink_finalize_message(msg, system_id, component_id, 33, 152); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uin uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; _mav_put_float(buf, 0, param1); _mav_put_float(buf, 4, param2); _mav_put_float(buf, 8, param3); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 31, target_component); _mav_put_uint8_t(buf, 32, confirmation); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); #else mavlink_command_long_t packet; packet.param1 = param1; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uin packet.target_component = target_component; packet.confirmation = confirmation; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 152); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; _mav_put_float(buf, 0, param1); _mav_put_float(buf, 4, param2); _mav_put_float(buf, 8, param3); @@ -204,7 +215,11 @@ static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t _mav_put_uint8_t(buf, 31, target_component); _mav_put_uint8_t(buf, 32, confirmation); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, 33, 152); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif #else mavlink_command_long_t packet; packet.param1 = param1; @@ -219,7 +234,11 @@ static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t packet.target_component = target_component; packet.confirmation = confirmation; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, 33, 152); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, command_long->target_component = mavlink_msg_command_long_get_target_component(msg); command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); #else - memcpy(command_long, _MAV_PAYLOAD(msg), 33); + memcpy(command_long, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_LONG_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h index e5ec290452f45c009051d9f098400787abfa645a..782ea9f26b4f6ee119cf5715d78ae15de059b8d5 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h @@ -12,6 +12,9 @@ typedef struct __mavlink_data_stream_t #define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 #define MAVLINK_MSG_ID_67_LEN 4 +#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 +#define MAVLINK_MSG_ID_67_CRC 21 + #define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c uint8_t stream_id, uint16_t message_rate, uint8_t on_off) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; _mav_put_uint16_t(buf, 0, message_rate); _mav_put_uint8_t(buf, 2, stream_id); _mav_put_uint8_t(buf, 3, on_off); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); #else mavlink_data_stream_t packet; packet.message_rate = message_rate; packet.stream_id = stream_id; packet.on_off = on_off; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; - return mavlink_finalize_message(msg, system_id, component_id, 4, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint uint8_t stream_id,uint16_t message_rate,uint8_t on_off) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; _mav_put_uint16_t(buf, 0, message_rate); _mav_put_uint8_t(buf, 2, stream_id); _mav_put_uint8_t(buf, 3, on_off); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); #else mavlink_data_stream_t packet; packet.message_rate = message_rate; packet.stream_id = stream_id; packet.on_off = on_off; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; _mav_put_uint16_t(buf, 0, message_rate); _mav_put_uint8_t(buf, 2, stream_id); _mav_put_uint8_t(buf, 3, on_off); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, 4, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif #else mavlink_data_stream_t packet; packet.message_rate = message_rate; packet.stream_id = stream_id; packet.on_off = on_off; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, 4, 21); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); #else - memcpy(data_stream, _MAV_PAYLOAD(msg), 4); + memcpy(data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_STREAM_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h index 5ff88e6a8a2cd9a71fe99bf9eb5296e591b9e456..a111619185acbae77df78cb2f291feb19729a2bb 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h @@ -12,6 +12,9 @@ typedef struct __mavlink_debug_t #define MAVLINK_MSG_ID_DEBUG_LEN 9 #define MAVLINK_MSG_ID_254_LEN 9 +#define MAVLINK_MSG_ID_DEBUG_CRC 46 +#define MAVLINK_MSG_ID_254_CRC 46 + #define MAVLINK_MESSAGE_INFO_DEBUG { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone uint32_t time_boot_ms, uint8_t ind, float value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, value); _mav_put_uint8_t(buf, 8, ind); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); #else mavlink_debug_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; packet.ind = ind; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message(msg, system_id, component_id, 9, 46); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co uint32_t time_boot_ms,uint8_t ind,float value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, value); _mav_put_uint8_t(buf, 8, ind); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); #else mavlink_debug_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; packet.ind = ind; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, value); _mav_put_uint8_t(buf, 8, ind); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, 9, 46); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); +#endif #else mavlink_debug_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; packet.ind = ind; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, 9, 46); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlin debug->value = mavlink_msg_debug_get_value(msg); debug->ind = mavlink_msg_debug_get_ind(msg); #else - memcpy(debug, _MAV_PAYLOAD(msg), 9); + memcpy(debug, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h index 0b443a061138eab5f5ffc8ed6caf5eafcd3d7f54..5ee4e323ac03dfad3449071dbe491bb5aef5d4ee 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h @@ -14,6 +14,9 @@ typedef struct __mavlink_debug_vect_t #define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 #define MAVLINK_MSG_ID_250_LEN 30 +#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 +#define MAVLINK_MSG_ID_250_CRC 49 + #define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 #define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ @@ -45,13 +48,13 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co const char *name, uint64_t time_usec, float x, float y, float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[30]; + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); _mav_put_char_array(buf, 20, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); #else mavlink_debug_vect_t packet; packet.time_usec = time_usec; @@ -59,11 +62,15 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co packet.y = y; packet.z = z; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; - return mavlink_finalize_message(msg, system_id, component_id, 30, 49); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif } /** @@ -84,13 +91,13 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8 const char *name,uint64_t time_usec,float x,float y,float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[30]; + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); _mav_put_char_array(buf, 20, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); #else mavlink_debug_vect_t packet; packet.time_usec = time_usec; @@ -98,11 +105,15 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8 packet.y = y; packet.z = z; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif } /** @@ -133,13 +144,17 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[30]; + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); _mav_put_char_array(buf, 20, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30, 49); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif #else mavlink_debug_vect_t packet; packet.time_usec = time_usec; @@ -147,7 +162,11 @@ static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const cha packet.y = y; packet.z = z; mav_array_memcpy(packet.name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30, 49); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif #endif } @@ -221,6 +240,6 @@ static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, m debug_vect->z = mavlink_msg_debug_vect_get_z(msg); mavlink_msg_debug_vect_get_name(msg, debug_vect->name); #else - memcpy(debug_vect, _MAV_PAYLOAD(msg), 30); + memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h index 27f5a91db0a57c48882f0d53693fc570458b7131..c026419a20d4ad11af4a3126c9d1be7fc767f2bf 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h @@ -12,6 +12,9 @@ typedef struct __mavlink_file_transfer_dir_list_t #define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249 #define MAVLINK_MSG_ID_111_LEN 249 +#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC 93 +#define MAVLINK_MSG_ID_111_CRC 93 + #define MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_DIR_PATH_LEN 240 #define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id uint64_t transfer_uid, const char *dir_path, uint8_t flags) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[249]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint8_t(buf, 248, flags); _mav_put_char_array(buf, 8, dir_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); #else mavlink_file_transfer_dir_list_t packet; packet.transfer_uid = transfer_uid; packet.flags = flags; mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST; - return mavlink_finalize_message(msg, system_id, component_id, 249, 93); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t syst uint64_t transfer_uid,const char *dir_path,uint8_t flags) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[249]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint8_t(buf, 248, flags); _mav_put_char_array(buf, 8, dir_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); #else mavlink_file_transfer_dir_list_t packet; packet.transfer_uid = transfer_uid; packet.flags = flags; mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 249, 93); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_ static inline void mavlink_msg_file_transfer_dir_list_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[249]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint8_t(buf, 248, flags); _mav_put_char_array(buf, 8, dir_path, 240); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, 249, 93); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); +#endif #else mavlink_file_transfer_dir_list_t packet; packet.transfer_uid = transfer_uid; packet.flags = flags; mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, 249, 93); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_file_transfer_dir_list_decode(const mavlink_messa mavlink_msg_file_transfer_dir_list_get_dir_path(msg, file_transfer_dir_list->dir_path); file_transfer_dir_list->flags = mavlink_msg_file_transfer_dir_list_get_flags(msg); #else - memcpy(file_transfer_dir_list, _MAV_PAYLOAD(msg), 249); + memcpy(file_transfer_dir_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h index f7035ec9e291d8a81168de98118f7122dba4da5e..86d407d66b8e88fb5af47feefe270062eb914060 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h @@ -11,6 +11,9 @@ typedef struct __mavlink_file_transfer_res_t #define MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9 #define MAVLINK_MSG_ID_112_LEN 9 +#define MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC 124 +#define MAVLINK_MSG_ID_112_CRC 124 + #define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uin uint64_t transfer_uid, uint8_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint8_t(buf, 8, result); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); #else mavlink_file_transfer_res_t packet; packet.transfer_uid = transfer_uid; packet.result = result; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES; - return mavlink_finalize_message(msg, system_id, component_id, 9, 124); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id uint64_t transfer_uid,uint8_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint8_t(buf, 8, result); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); #else mavlink_file_transfer_res_t packet; packet.transfer_uid = transfer_uid; packet.result = result; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 124); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, u static inline void mavlink_msg_file_transfer_res_send(mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint8_t(buf, 8, result); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, 9, 124); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); +#endif #else mavlink_file_transfer_res_t packet; packet.transfer_uid = transfer_uid; packet.result = result; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, 9, 124); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_file_transfer_res_decode(const mavlink_message_t* file_transfer_res->transfer_uid = mavlink_msg_file_transfer_res_get_transfer_uid(msg); file_transfer_res->result = mavlink_msg_file_transfer_res_get_result(msg); #else - memcpy(file_transfer_res, _MAV_PAYLOAD(msg), 9); + memcpy(file_transfer_res, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h index 5eaa9b2207177f0e8cb106c3092af0ec94c94393..24bf25413f9f343c681818b29970fe2bea1766c7 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h @@ -14,6 +14,9 @@ typedef struct __mavlink_file_transfer_start_t #define MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254 #define MAVLINK_MSG_ID_110_LEN 254 +#define MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC 235 +#define MAVLINK_MSG_ID_110_CRC 235 + #define MAVLINK_MSG_FILE_TRANSFER_START_FIELD_DEST_PATH_LEN 240 #define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START { \ @@ -45,13 +48,13 @@ static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, u uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[254]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint32_t(buf, 8, file_size); _mav_put_uint8_t(buf, 252, direction); _mav_put_uint8_t(buf, 253, flags); _mav_put_char_array(buf, 12, dest_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); #else mavlink_file_transfer_start_t packet; packet.transfer_uid = transfer_uid; @@ -59,11 +62,15 @@ static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, u packet.direction = direction; packet.flags = flags; mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START; - return mavlink_finalize_message(msg, system_id, component_id, 254, 235); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); +#endif } /** @@ -84,13 +91,13 @@ static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_ uint64_t transfer_uid,const char *dest_path,uint8_t direction,uint32_t file_size,uint8_t flags) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[254]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint32_t(buf, 8, file_size); _mav_put_uint8_t(buf, 252, direction); _mav_put_uint8_t(buf, 253, flags); _mav_put_char_array(buf, 12, dest_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); #else mavlink_file_transfer_start_t packet; packet.transfer_uid = transfer_uid; @@ -98,11 +105,15 @@ static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_ packet.direction = direction; packet.flags = flags; mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 254, 235); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); +#endif } /** @@ -133,13 +144,17 @@ static inline uint16_t mavlink_msg_file_transfer_start_encode(uint8_t system_id, static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[254]; + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN]; _mav_put_uint64_t(buf, 0, transfer_uid); _mav_put_uint32_t(buf, 8, file_size); _mav_put_uint8_t(buf, 252, direction); _mav_put_uint8_t(buf, 253, flags); _mav_put_char_array(buf, 12, dest_path, 240); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, 254, 235); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); +#endif #else mavlink_file_transfer_start_t packet; packet.transfer_uid = transfer_uid; @@ -147,7 +162,11 @@ static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan, packet.direction = direction; packet.flags = flags; mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, 254, 235); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); +#endif #endif } @@ -221,6 +240,6 @@ static inline void mavlink_msg_file_transfer_start_decode(const mavlink_message_ file_transfer_start->direction = mavlink_msg_file_transfer_start_get_direction(msg); file_transfer_start->flags = mavlink_msg_file_transfer_start_get_flags(msg); #else - memcpy(file_transfer_start, _MAV_PAYLOAD(msg), 254); + memcpy(file_transfer_start, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h index 780f562c5b690b605553aac4d958602e1944af75..11ab97ee47f58bf14a13e38cbefde005827e7285 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h @@ -18,6 +18,9 @@ typedef struct __mavlink_global_position_int_t #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 #define MAVLINK_MSG_ID_33_LEN 28 +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 +#define MAVLINK_MSG_ID_33_CRC 104 + #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, lat); _mav_put_int32_t(buf, 8, lon); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u _mav_put_int16_t(buf, 24, vz); _mav_put_uint16_t(buf, 26, hdg); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); #else mavlink_global_position_int_t packet; packet.time_boot_ms = time_boot_ms; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u packet.vz = vz; packet.hdg = hdg; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; - return mavlink_finalize_message(msg, system_id, component_id, 28, 104); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_ uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, lat); _mav_put_int32_t(buf, 8, lon); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_ _mav_put_int16_t(buf, 24, vz); _mav_put_uint16_t(buf, 26, hdg); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); #else mavlink_global_position_int_t packet; packet.time_boot_ms = time_boot_ms; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_ packet.vz = vz; packet.hdg = hdg; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 104); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, lat); _mav_put_int32_t(buf, 8, lon); @@ -184,7 +195,11 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, _mav_put_int16_t(buf, 24, vz); _mav_put_uint16_t(buf, 26, hdg); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 28, 104); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif #else mavlink_global_position_int_t packet; packet.time_boot_ms = time_boot_ms; @@ -197,7 +212,11 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, packet.vz = vz; packet.hdg = hdg; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 28, 104); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_global_position_int_decode(const mavlink_message_ global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); #else - memcpy(global_position_int, _MAV_PAYLOAD(msg), 28); + memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h index 853b85daeb3f5b602dbd56b1a12674567b0aeead..8153628aa80be38248c9d155d9ec87d05626c706 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h @@ -4,9 +4,9 @@ typedef struct __mavlink_global_position_setpoint_int_t { - int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7 - int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7 - int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up) + int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 + int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7 + int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) int16_t yaw; ///< Desired yaw angle in degrees * 100 uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT } mavlink_global_position_setpoint_int_t; @@ -14,6 +14,9 @@ typedef struct __mavlink_global_position_setpoint_int_t #define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15 #define MAVLINK_MSG_ID_52_LEN 15 +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC 141 +#define MAVLINK_MSG_ID_52_CRC 141 + #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \ @@ -35,9 +38,9 @@ typedef struct __mavlink_global_position_setpoint_int_t * @param msg The MAVLink message to compress the data into * * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude WGS84 Latitude position in degrees * 1E7 - * @param longitude WGS84 Longitude position in degrees * 1E7 - * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @param yaw Desired yaw angle in degrees * 100 * @return length of the message in bytes (excluding serial stream start sign) */ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t sys uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_int16_t(buf, 12, yaw); _mav_put_uint8_t(buf, 14, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); #else mavlink_global_position_setpoint_int_t packet; packet.latitude = latitude; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t sys packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; - return mavlink_finalize_message(msg, system_id, component_id, 15, 141); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif } /** @@ -75,9 +82,9 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t sys * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude WGS84 Latitude position in degrees * 1E7 - * @param longitude WGS84 Longitude position in degrees * 1E7 - * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @param yaw Desired yaw angle in degrees * 100 * @return length of the message in bytes (excluding serial stream start sign) */ @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_ uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_int16_t(buf, 12, yaw); _mav_put_uint8_t(buf, 14, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); #else mavlink_global_position_setpoint_int_t packet; packet.latitude = latitude; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_ packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 141); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif } /** @@ -127,9 +138,9 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t s * @param chan MAVLink channel to send the message * * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude WGS84 Latitude position in degrees * 1E7 - * @param longitude WGS84 Longitude position in degrees * 1E7 - * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @param yaw Desired yaw angle in degrees * 100 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t s static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_int16_t(buf, 12, yaw); _mav_put_uint8_t(buf, 14, coordinate_frame); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 141); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif #else mavlink_global_position_setpoint_int_t packet; packet.latitude = latitude; @@ -153,7 +168,11 @@ static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 141); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif #endif } @@ -175,7 +194,7 @@ static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_fr /** * @brief Get field latitude from global_position_setpoint_int message * - * @return WGS84 Latitude position in degrees * 1E7 + * @return Latitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) { @@ -185,7 +204,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(cons /** * @brief Get field longitude from global_position_setpoint_int message * - * @return WGS84 Longitude position in degrees * 1E7 + * @return Longitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) { @@ -195,7 +214,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(con /** * @brief Get field altitude from global_position_setpoint_int message * - * @return WGS84 Altitude in meters * 1000 (positive for up) + * @return Altitude (WGS84), in meters * 1000 (positive for up) */ static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) { @@ -227,6 +246,6 @@ static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg); global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg); #else - memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 15); + memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h index a911fe25ef8f44420df1ce901d673f30264764f2..b388fa24add458a3558bb87cf9a597b37d7b67c1 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h @@ -16,6 +16,9 @@ typedef struct __mavlink_global_vision_position_estimate_t #define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 #define MAVLINK_MSG_ID_101_LEN 32 +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 +#define MAVLINK_MSG_ID_101_CRC 102 + #define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); #else mavlink_global_vision_position_estimate_t packet; packet.usec = usec; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 32, 102); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); #else mavlink_global_vision_position_estimate_t packet; packet.usec = usec; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 102); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -164,7 +175,11 @@ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_chan _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, 32, 102); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif #else mavlink_global_vision_position_estimate_t packet; packet.usec = usec; @@ -175,7 +190,11 @@ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_chan packet.pitch = pitch; packet.yaw = yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 102); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_global_vision_position_estimate_decode(const mavl global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); #else - memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), 32); + memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h index 2084718b5d26b99fd773235585fd62b0262ddcc0..bd09cb753447c4aebf4070dac1f22c81e90de5ee 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h @@ -4,14 +4,17 @@ typedef struct __mavlink_gps_global_origin_t { - int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7 - int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7 - int32_t altitude; ///< Altitude(WGS84), expressed as * 1000 + int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 + int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7 + int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) } mavlink_gps_global_origin_t; #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 #define MAVLINK_MSG_ID_49_LEN 12 +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 +#define MAVLINK_MSG_ID_49_CRC 39 + #define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ @@ -30,32 +33,36 @@ typedef struct __mavlink_gps_global_origin_t * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param latitude Latitude (WGS84), expressed as * 1E7 - * @param longitude Longitude (WGS84), expressed as * 1E7 - * @param altitude Altitude(WGS84), expressed as * 1000 + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); #else mavlink_gps_global_origin_t packet; packet.latitude = latitude; packet.longitude = longitude; packet.altitude = altitude; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message(msg, system_id, component_id, 12, 39); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif } /** @@ -64,9 +71,9 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), expressed as * 1E7 - * @param longitude Longitude (WGS84), expressed as * 1E7 - * @param altitude Altitude(WGS84), expressed as * 1000 + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id int32_t latitude,int32_t longitude,int32_t altitude) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); #else mavlink_gps_global_origin_t packet; packet.latitude = latitude; packet.longitude = longitude; packet.altitude = altitude; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif } /** @@ -110,28 +121,36 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, u * @brief Send a gps_global_origin message * @param chan MAVLink channel to send the message * - * @param latitude Latitude (WGS84), expressed as * 1E7 - * @param longitude Longitude (WGS84), expressed as * 1E7 - * @param altitude Altitude(WGS84), expressed as * 1000 + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, 12, 39); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif #else mavlink_gps_global_origin_t packet; packet.latitude = latitude; packet.longitude = longitude; packet.altitude = altitude; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, 12, 39); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif #endif } @@ -143,7 +162,7 @@ static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, in /** * @brief Get field latitude from gps_global_origin message * - * @return Latitude (WGS84), expressed as * 1E7 + * @return Latitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) { @@ -153,7 +172,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_m /** * @brief Get field longitude from gps_global_origin message * - * @return Longitude (WGS84), expressed as * 1E7 + * @return Longitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) { @@ -163,7 +182,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_ /** * @brief Get field altitude from gps_global_origin message * - * @return Altitude(WGS84), expressed as * 1000 + * @return Altitude (WGS84), in meters * 1000 (positive for up) */ static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) { @@ -183,6 +202,6 @@ static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); #else - memcpy(gps_global_origin, _MAV_PAYLOAD(msg), 12); + memcpy(gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h index 57ec97376327f784a3816d57c251e478820b8c23..2136b65eef4c6011e570431f1a7d6ae8c0f5c99f 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h @@ -5,9 +5,9 @@ typedef struct __mavlink_gps_raw_int_t { uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - int32_t lat; ///< Latitude in 1E7 degrees - int32_t lon; ///< Longitude in 1E7 degrees - int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL + int32_t lat; ///< Latitude (WGS84), in degrees * 1E7 + int32_t lon; ///< Longitude (WGS84), in degrees * 1E7 + int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up) uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535 @@ -19,6 +19,9 @@ typedef struct __mavlink_gps_raw_int_t #define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 #define MAVLINK_MSG_ID_24_LEN 30 +#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 +#define MAVLINK_MSG_ID_24_CRC 24 + #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ @@ -46,9 +49,9 @@ typedef struct __mavlink_gps_raw_int_t * * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude in 1E7 degrees - * @param lon Longitude in 1E7 degrees - * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[30]; + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int32_t(buf, 8, lat); _mav_put_int32_t(buf, 12, lon); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c _mav_put_uint8_t(buf, 28, fix_type); _mav_put_uint8_t(buf, 29, satellites_visible); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); #else mavlink_gps_raw_int_t packet; packet.time_usec = time_usec; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c packet.fix_type = fix_type; packet.satellites_visible = satellites_visible; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; - return mavlink_finalize_message(msg, system_id, component_id, 30, 24); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif } /** @@ -101,9 +108,9 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c * @param msg The MAVLink message to compress the data into * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude in 1E7 degrees - * @param lon Longitude in 1E7 degrees - * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[30]; + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int32_t(buf, 8, lat); _mav_put_int32_t(buf, 12, lon); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint _mav_put_uint8_t(buf, 28, fix_type); _mav_put_uint8_t(buf, 29, satellites_visible); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); #else mavlink_gps_raw_int_t packet; packet.time_usec = time_usec; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint packet.fix_type = fix_type; packet.satellites_visible = satellites_visible; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 24); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif } /** @@ -168,9 +179,9 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t * * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude in 1E7 degrees - * @param lon Longitude in 1E7 degrees - * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (WGS84), in meters * 1000 (positive for up) * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[30]; + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int32_t(buf, 8, lat); _mav_put_int32_t(buf, 12, lon); @@ -194,7 +205,11 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t _mav_put_uint8_t(buf, 28, fix_type); _mav_put_uint8_t(buf, 29, satellites_visible); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, 30, 24); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif #else mavlink_gps_raw_int_t packet; packet.time_usec = time_usec; @@ -208,7 +223,11 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t packet.fix_type = fix_type; packet.satellites_visible = satellites_visible; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, 30, 24); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif #endif } @@ -240,7 +259,7 @@ static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message /** * @brief Get field lat from gps_raw_int message * - * @return Latitude in 1E7 degrees + * @return Latitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) { @@ -250,7 +269,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* m /** * @brief Get field lon from gps_raw_int message * - * @return Longitude in 1E7 degrees + * @return Longitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) { @@ -260,7 +279,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* m /** * @brief Get field alt from gps_raw_int message * - * @return Altitude in 1E3 meters (millimeters) above MSL + * @return Altitude (WGS84), in meters * 1000 (positive for up) */ static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) { @@ -337,6 +356,6 @@ static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); #else - memcpy(gps_raw_int, _MAV_PAYLOAD(msg), 30); + memcpy(gps_raw_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RAW_INT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h index bd3257f889b58c7bc7928a18e9d26ca583cbcba1..cd6dde700f575f12ad69c60043879b6baa40d3dc 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h @@ -15,6 +15,9 @@ typedef struct __mavlink_gps_status_t #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 #define MAVLINK_MSG_ID_25_LEN 101 +#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23 +#define MAVLINK_MSG_ID_25_CRC 23 + #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 @@ -52,14 +55,14 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[101]; + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; _mav_put_uint8_t(buf, 0, satellites_visible); _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); _mav_put_uint8_t_array(buf, 21, satellite_used, 20); _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); #else mavlink_gps_status_t packet; packet.satellites_visible = satellites_visible; @@ -68,11 +71,15 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 101, 23); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif } /** @@ -94,14 +101,14 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8 uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[101]; + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; _mav_put_uint8_t(buf, 0, satellites_visible); _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); _mav_put_uint8_t_array(buf, 21, satellite_used, 20); _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); #else mavlink_gps_status_t packet; packet.satellites_visible = satellites_visible; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8 mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif } /** @@ -146,14 +157,18 @@ static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[101]; + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; _mav_put_uint8_t(buf, 0, satellites_visible); _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); _mav_put_uint8_t_array(buf, 21, satellite_used, 20); _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif #else mavlink_gps_status_t packet; packet.satellites_visible = satellites_visible; @@ -162,7 +177,11 @@ static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t s mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif #endif } @@ -247,6 +266,6 @@ static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, m mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); #else - memcpy(gps_status, _MAV_PAYLOAD(msg), 101); + memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h index 599ea0bc5e9f6b95e1f290ec004610066b1e773a..b2f0b65d064bb7f183186f63c8026d599de74d40 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h @@ -15,6 +15,9 @@ typedef struct __mavlink_heartbeat_t #define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 #define MAVLINK_MSG_ID_0_LEN 9 +#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 +#define MAVLINK_MSG_ID_0_CRC 50 + #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ @@ -47,7 +50,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; _mav_put_uint32_t(buf, 0, custom_mode); _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 5, autopilot); @@ -55,7 +58,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com _mav_put_uint8_t(buf, 7, system_status); _mav_put_uint8_t(buf, 8, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); #else mavlink_heartbeat_t packet; packet.custom_mode = custom_mode; @@ -65,11 +68,15 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com packet.system_status = system_status; packet.mavlink_version = 3; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; - return mavlink_finalize_message(msg, system_id, component_id, 9, 50); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif } /** @@ -90,7 +97,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_ uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; _mav_put_uint32_t(buf, 0, custom_mode); _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 5, autopilot); @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 7, system_status); _mav_put_uint8_t(buf, 8, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); #else mavlink_heartbeat_t packet; packet.custom_mode = custom_mode; @@ -108,11 +115,15 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_ packet.system_status = system_status; packet.mavlink_version = 3; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif } /** @@ -143,7 +154,7 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; _mav_put_uint32_t(buf, 0, custom_mode); _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 5, autopilot); @@ -151,7 +162,11 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty _mav_put_uint8_t(buf, 7, system_status); _mav_put_uint8_t(buf, 8, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif #else mavlink_heartbeat_t packet; packet.custom_mode = custom_mode; @@ -161,7 +176,11 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty packet.system_status = system_status; packet.mavlink_version = 3; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif #endif } @@ -246,6 +265,6 @@ static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, ma heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); #else - memcpy(heartbeat, _MAV_PAYLOAD(msg), 9); + memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h index 9714c698faba3973263eb9d88533bbf80d7e689a..6e7492ea65e236303b9501f8b9df869388e0a1b8 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h @@ -24,6 +24,9 @@ typedef struct __mavlink_highres_imu_t #define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 #define MAVLINK_MSG_ID_105_LEN 62 +#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 +#define MAVLINK_MSG_ID_105_CRC 93 + #define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ @@ -75,7 +78,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[62]; + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, xacc); _mav_put_float(buf, 12, yacc); @@ -92,7 +95,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c _mav_put_float(buf, 56, temperature); _mav_put_uint16_t(buf, 60, fields_updated); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 62); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); #else mavlink_highres_imu_t packet; packet.time_usec = time_usec; @@ -111,11 +114,15 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c packet.temperature = temperature; packet.fields_updated = fields_updated; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 62); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; - return mavlink_finalize_message(msg, system_id, component_id, 62, 93); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif } /** @@ -146,7 +153,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint16_t fields_updated) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[62]; + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, xacc); _mav_put_float(buf, 12, yacc); @@ -163,7 +170,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint _mav_put_float(buf, 56, temperature); _mav_put_uint16_t(buf, 60, fields_updated); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 62); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); #else mavlink_highres_imu_t packet; packet.time_usec = time_usec; @@ -182,11 +189,15 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint packet.temperature = temperature; packet.fields_updated = fields_updated; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 62); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 62, 93); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif } /** @@ -227,7 +238,7 @@ static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[62]; + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, xacc); _mav_put_float(buf, 12, yacc); @@ -244,7 +255,11 @@ static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t _mav_put_float(buf, 56, temperature); _mav_put_uint16_t(buf, 60, fields_updated); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, 62, 93); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif #else mavlink_highres_imu_t packet; packet.time_usec = time_usec; @@ -263,7 +278,11 @@ static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t packet.temperature = temperature; packet.fields_updated = fields_updated; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, 62, 93); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif #endif } @@ -447,6 +466,6 @@ static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); #else - memcpy(highres_imu, _MAV_PAYLOAD(msg), 62); + memcpy(highres_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIGHRES_IMU_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h index 41a9bc9498b63aa0134310d8e1db72df517df75d..3319d3fd2d0d06fb6dc05a4812c0d447b25f5619 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h @@ -20,6 +20,9 @@ typedef struct __mavlink_hil_controls_t #define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 #define MAVLINK_MSG_ID_91_LEN 42 +#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 +#define MAVLINK_MSG_ID_91_CRC 63 + #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[42]; + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, roll_ailerons); _mav_put_float(buf, 12, pitch_elevator); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 40, mode); _mav_put_uint8_t(buf, 41, nav_mode); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); #else mavlink_hil_controls_t packet; packet.time_usec = time_usec; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t packet.mode = mode; packet.nav_mode = nav_mode; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; - return mavlink_finalize_message(msg, system_id, component_id, 42, 63); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[42]; + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, roll_ailerons); _mav_put_float(buf, 12, pitch_elevator); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 40, mode); _mav_put_uint8_t(buf, 41, nav_mode); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); #else mavlink_hil_controls_t packet; packet.time_usec = time_usec; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin packet.mode = mode; packet.nav_mode = nav_mode; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 63); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[42]; + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, roll_ailerons); _mav_put_float(buf, 12, pitch_elevator); @@ -204,7 +215,11 @@ static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_ _mav_put_uint8_t(buf, 40, mode); _mav_put_uint8_t(buf, 41, nav_mode); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, 42, 63); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif #else mavlink_hil_controls_t packet; packet.time_usec = time_usec; @@ -219,7 +234,11 @@ static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_ packet.mode = mode; packet.nav_mode = nav_mode; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, 42, 63); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); #else - memcpy(hil_controls, _MAV_PAYLOAD(msg), 42); + memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h index 7ac0853d31871b173e092784a1063672bbc750bd..f2435dde8716d81732f94bdf28e31e48bd18f317 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h @@ -23,6 +23,9 @@ typedef struct __mavlink_hil_rc_inputs_raw_t #define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 #define MAVLINK_MSG_ID_92_LEN 33 +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 +#define MAVLINK_MSG_ID_92_CRC 54 + #define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uin uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_uint16_t(buf, 8, chan1_raw); _mav_put_uint16_t(buf, 10, chan2_raw); @@ -88,7 +91,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uin _mav_put_uint16_t(buf, 30, chan12_raw); _mav_put_uint8_t(buf, 32, rssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); #else mavlink_hil_rc_inputs_raw_t packet; packet.time_usec = time_usec; @@ -106,11 +109,15 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uin packet.chan12_raw = chan12_raw; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; - return mavlink_finalize_message(msg, system_id, component_id, 33, 54); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif } /** @@ -140,7 +147,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_uint16_t(buf, 8, chan1_raw); _mav_put_uint16_t(buf, 10, chan2_raw); @@ -156,7 +163,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id _mav_put_uint16_t(buf, 30, chan12_raw); _mav_put_uint8_t(buf, 32, rssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); #else mavlink_hil_rc_inputs_raw_t packet; packet.time_usec = time_usec; @@ -174,11 +181,15 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id packet.chan12_raw = chan12_raw; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 54); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif } /** @@ -218,7 +229,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, u static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_uint16_t(buf, 8, chan1_raw); _mav_put_uint16_t(buf, 10, chan2_raw); @@ -234,7 +245,11 @@ static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, ui _mav_put_uint16_t(buf, 30, chan12_raw); _mav_put_uint8_t(buf, 32, rssi); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, 33, 54); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif #else mavlink_hil_rc_inputs_raw_t packet; packet.time_usec = time_usec; @@ -252,7 +267,11 @@ static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, ui packet.chan12_raw = chan12_raw; packet.rssi = rssi; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, 33, 54); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif #endif } @@ -425,6 +444,6 @@ static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); #else - memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), 33); + memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h new file mode 100644 index 0000000000000000000000000000000000000000..d5a07bc32b7caf8248049cb0ed329e3b2a11c56e --- /dev/null +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h @@ -0,0 +1,603 @@ +// MESSAGE HIL_SENSOR PACKING + +#define MAVLINK_MSG_ID_HIL_SENSOR 107 + +typedef struct __mavlink_hil_sensor_t +{ + uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) + float roll; ///< Roll angle in inertial frame (rad) + float pitch; ///< Pitch angle in inertial frame (rad) + float yaw; ///< Yaw angle in inertial frame (rad) + int32_t lat; ///< Latitude, expressed as * 1E7 degrees + int32_t lon; ///< Longitude, expressed as * 1E7 degrees + float xacc; ///< X acceleration (m/s^2) + float yacc; ///< Y acceleration (m/s^2) + float zacc; ///< Z acceleration (m/s^2) + float xgyro; ///< Angular speed around X axis in body frame (rad / sec) + float ygyro; ///< Angular speed around Y axis in body frame (rad / sec) + float zgyro; ///< Angular speed around Z axis in body frame (rad / sec) + float xmag; ///< X Magnetic field (Gauss) + float ymag; ///< Y Magnetic field (Gauss) + float zmag; ///< Z Magnetic field (Gauss) + float abs_pressure; ///< Absolute pressure in millibar + float diff_pressure; ///< Differential pressure (airspeed) in millibar + float pressure_alt; ///< Altitude calculated from pressure + float gps_alt; ///< GPS altitude (MSL) WGS84 + float temperature; ///< Temperature in degrees celsius + uint32_t fields_updated; ///< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature +} mavlink_hil_sensor_t; + +#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 88 +#define MAVLINK_MSG_ID_107_LEN 88 + +#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 5 +#define MAVLINK_MSG_ID_107_CRC 5 + + + +#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ + "HIL_SENSOR", \ + 21, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, yaw) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_hil_sensor_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_hil_sensor_t, lon) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_hil_sensor_t, zmag) }, \ + { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ + { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ + { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_hil_sensor_t, gps_alt) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_hil_sensor_t, temperature) }, \ + { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 84, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ + } \ +} + + +/** + * @brief Pack a hil_sensor 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 time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param roll Roll angle in inertial frame (rad) + * @param pitch Pitch angle in inertial frame (rad) + * @param yaw Yaw angle in inertial frame (rad) + * @param lat Latitude, expressed as * 1E7 degrees + * @param lon Longitude, expressed as * 1E7 degrees + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param gps_alt GPS altitude (MSL) WGS84 + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll, float pitch, float yaw, int32_t lat, int32_t lon, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float gps_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_int32_t(buf, 20, lat); + _mav_put_int32_t(buf, 24, lon); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, xmag); + _mav_put_float(buf, 56, ymag); + _mav_put_float(buf, 60, zmag); + _mav_put_float(buf, 64, abs_pressure); + _mav_put_float(buf, 68, diff_pressure); + _mav_put_float(buf, 72, pressure_alt); + _mav_put_float(buf, 76, gps_alt); + _mav_put_float(buf, 80, temperature); + _mav_put_uint32_t(buf, 84, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.lat = lat; + packet.lon = lon; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.gps_alt = gps_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} + +/** + * @brief Pack a hil_sensor message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param roll Roll angle in inertial frame (rad) + * @param pitch Pitch angle in inertial frame (rad) + * @param yaw Yaw angle in inertial frame (rad) + * @param lat Latitude, expressed as * 1E7 degrees + * @param lon Longitude, expressed as * 1E7 degrees + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param gps_alt GPS altitude (MSL) WGS84 + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll,float pitch,float yaw,int32_t lat,int32_t lon,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float gps_alt,float temperature,uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_int32_t(buf, 20, lat); + _mav_put_int32_t(buf, 24, lon); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, xmag); + _mav_put_float(buf, 56, ymag); + _mav_put_float(buf, 60, zmag); + _mav_put_float(buf, 64, abs_pressure); + _mav_put_float(buf, 68, diff_pressure); + _mav_put_float(buf, 72, pressure_alt); + _mav_put_float(buf, 76, gps_alt); + _mav_put_float(buf, 80, temperature); + _mav_put_uint32_t(buf, 84, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.lat = lat; + packet.lon = lon; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.gps_alt = gps_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} + +/** + * @brief Encode a hil_sensor 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 hil_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) +{ + return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->roll, hil_sensor->pitch, hil_sensor->yaw, hil_sensor->lat, hil_sensor->lon, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->gps_alt, hil_sensor->temperature, hil_sensor->fields_updated); +} + +/** + * @brief Send a hil_sensor message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param roll Roll angle in inertial frame (rad) + * @param pitch Pitch angle in inertial frame (rad) + * @param yaw Yaw angle in inertial frame (rad) + * @param lat Latitude, expressed as * 1E7 degrees + * @param lon Longitude, expressed as * 1E7 degrees + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param gps_alt GPS altitude (MSL) WGS84 + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, int32_t lat, int32_t lon, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float gps_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_int32_t(buf, 20, lat); + _mav_put_int32_t(buf, 24, lon); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, xmag); + _mav_put_float(buf, 56, ymag); + _mav_put_float(buf, 60, zmag); + _mav_put_float(buf, 64, abs_pressure); + _mav_put_float(buf, 68, diff_pressure); + _mav_put_float(buf, 72, pressure_alt); + _mav_put_float(buf, 76, gps_alt); + _mav_put_float(buf, 80, temperature); + _mav_put_uint32_t(buf, 84, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.lat = lat; + packet.lon = lon; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.gps_alt = gps_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#endif +} + +#endif + +// MESSAGE HIL_SENSOR UNPACKING + + +/** + * @brief Get field time_usec from hil_sensor message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll from hil_sensor message + * + * @return Roll angle in inertial frame (rad) + */ +static inline float mavlink_msg_hil_sensor_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch from hil_sensor message + * + * @return Pitch angle in inertial frame (rad) + */ +static inline float mavlink_msg_hil_sensor_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw from hil_sensor message + * + * @return Yaw angle in inertial frame (rad) + */ +static inline float mavlink_msg_hil_sensor_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field lat from hil_sensor message + * + * @return Latitude, expressed as * 1E7 degrees + */ +static inline int32_t mavlink_msg_hil_sensor_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field lon from hil_sensor message + * + * @return Longitude, expressed as * 1E7 degrees + */ +static inline int32_t mavlink_msg_hil_sensor_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Get field xacc from hil_sensor message + * + * @return X acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field yacc from hil_sensor message + * + * @return Y acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field zacc from hil_sensor message + * + * @return Z acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field xgyro from hil_sensor message + * + * @return Angular speed around X axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field ygyro from hil_sensor message + * + * @return Angular speed around Y axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field zgyro from hil_sensor message + * + * @return Angular speed around Z axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field xmag from hil_sensor message + * + * @return X Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field ymag from hil_sensor message + * + * @return Y Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field zmag from hil_sensor message + * + * @return Z Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 60); +} + +/** + * @brief Get field abs_pressure from hil_sensor message + * + * @return Absolute pressure in millibar + */ +static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 64); +} + +/** + * @brief Get field diff_pressure from hil_sensor message + * + * @return Differential pressure (airspeed) in millibar + */ +static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 68); +} + +/** + * @brief Get field pressure_alt from hil_sensor message + * + * @return Altitude calculated from pressure + */ +static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 72); +} + +/** + * @brief Get field gps_alt from hil_sensor message + * + * @return GPS altitude (MSL) WGS84 + */ +static inline float mavlink_msg_hil_sensor_get_gps_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 76); +} + +/** + * @brief Get field temperature from hil_sensor message + * + * @return Temperature in degrees celsius + */ +static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 80); +} + +/** + * @brief Get field fields_updated from hil_sensor message + * + * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + */ +static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 84); +} + +/** + * @brief Decode a hil_sensor message into a struct + * + * @param msg The message to decode + * @param hil_sensor C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, mavlink_hil_sensor_t* hil_sensor) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(msg); + hil_sensor->roll = mavlink_msg_hil_sensor_get_roll(msg); + hil_sensor->pitch = mavlink_msg_hil_sensor_get_pitch(msg); + hil_sensor->yaw = mavlink_msg_hil_sensor_get_yaw(msg); + hil_sensor->lat = mavlink_msg_hil_sensor_get_lat(msg); + hil_sensor->lon = mavlink_msg_hil_sensor_get_lon(msg); + hil_sensor->xacc = mavlink_msg_hil_sensor_get_xacc(msg); + hil_sensor->yacc = mavlink_msg_hil_sensor_get_yacc(msg); + hil_sensor->zacc = mavlink_msg_hil_sensor_get_zacc(msg); + hil_sensor->xgyro = mavlink_msg_hil_sensor_get_xgyro(msg); + hil_sensor->ygyro = mavlink_msg_hil_sensor_get_ygyro(msg); + hil_sensor->zgyro = mavlink_msg_hil_sensor_get_zgyro(msg); + hil_sensor->xmag = mavlink_msg_hil_sensor_get_xmag(msg); + hil_sensor->ymag = mavlink_msg_hil_sensor_get_ymag(msg); + hil_sensor->zmag = mavlink_msg_hil_sensor_get_zmag(msg); + hil_sensor->abs_pressure = mavlink_msg_hil_sensor_get_abs_pressure(msg); + hil_sensor->diff_pressure = mavlink_msg_hil_sensor_get_diff_pressure(msg); + hil_sensor->pressure_alt = mavlink_msg_hil_sensor_get_pressure_alt(msg); + hil_sensor->gps_alt = mavlink_msg_hil_sensor_get_gps_alt(msg); + hil_sensor->temperature = mavlink_msg_hil_sensor_get_temperature(msg); + hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); +#else + memcpy(hil_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h index 1447812956a12f273199a5289d85977bb138fcd4..a27f19cde679e07f7dbab4ffed160e18c95a6bc6 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h @@ -25,6 +25,9 @@ typedef struct __mavlink_hil_state_t #define MAVLINK_MSG_ID_HIL_STATE_LEN 56 #define MAVLINK_MSG_ID_90_LEN 56 +#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 +#define MAVLINK_MSG_ID_90_CRC 183 + #define MAVLINK_MESSAGE_INFO_HIL_STATE { \ @@ -78,7 +81,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com uint64_t time_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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[56]; + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, roll); _mav_put_float(buf, 12, pitch); @@ -96,7 +99,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com _mav_put_int16_t(buf, 52, yacc); _mav_put_int16_t(buf, 54, zacc); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); #else mavlink_hil_state_t packet; packet.time_usec = time_usec; @@ -116,11 +119,15 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com packet.yacc = yacc; packet.zacc = zacc; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIL_STATE; - return mavlink_finalize_message(msg, system_id, component_id, 56, 183); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif } /** @@ -152,7 +159,7 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_ uint64_t time_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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[56]; + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, roll); _mav_put_float(buf, 12, pitch); @@ -170,7 +177,7 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_ _mav_put_int16_t(buf, 52, yacc); _mav_put_int16_t(buf, 54, zacc); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); #else mavlink_hil_state_t packet; packet.time_usec = time_usec; @@ -190,11 +197,15 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_ packet.yacc = yacc; packet.zacc = zacc; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_HIL_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif } /** @@ -236,7 +247,7 @@ static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t c static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[56]; + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, roll); _mav_put_float(buf, 12, pitch); @@ -254,7 +265,11 @@ static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t t _mav_put_int16_t(buf, 52, yacc); _mav_put_int16_t(buf, 54, zacc); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56, 183); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif #else mavlink_hil_state_t packet; packet.time_usec = time_usec; @@ -274,7 +289,11 @@ static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t t packet.yacc = yacc; packet.zacc = zacc; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56, 183); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif #endif } @@ -469,6 +488,6 @@ static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, ma hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); #else - memcpy(hil_state, _MAV_PAYLOAD(msg), 56); + memcpy(hil_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h index fe0a791fc5c0449268d7b3fd81f59c07f8936e1d..56723f3d7d3b7ec0d80087513723dfb5665bcade 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h @@ -16,6 +16,9 @@ typedef struct __mavlink_local_position_ned_t #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 #define MAVLINK_MSG_ID_32_LEN 28 +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 +#define MAVLINK_MSG_ID_32_CRC 185 + #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, ui uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, x); _mav_put_float(buf, 8, y); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, ui _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); #else mavlink_local_position_ned_t packet; packet.time_boot_ms = time_boot_ms; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, ui packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; - return mavlink_finalize_message(msg, system_id, component_id, 28, 185); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_i uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, x); _mav_put_float(buf, 8, y); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_i _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); #else mavlink_local_position_ned_t packet; packet.time_boot_ms = time_boot_ms; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_i packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 185); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, x); _mav_put_float(buf, 8, y); @@ -164,7 +175,11 @@ static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, u _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, 28, 185); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif #else mavlink_local_position_ned_t packet; packet.time_boot_ms = time_boot_ms; @@ -175,7 +190,11 @@ static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, u packet.vy = vy; packet.vz = vz; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, 28, 185); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); #else - memcpy(local_position_ned, _MAV_PAYLOAD(msg), 28); + memcpy(local_position_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h index ac1941db091323375b5b6a2759df602351804702..c206a2906b4c0bc206604b04248ed00235c3ad84 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h @@ -16,6 +16,9 @@ typedef struct __mavlink_local_position_ned_system_global_offset_t #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 #define MAVLINK_MSG_ID_89_LEN 28 +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 +#define MAVLINK_MSG_ID_89_CRC 231 + #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack( uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, x); _mav_put_float(buf, 8, y); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack( _mav_put_float(buf, 20, pitch); _mav_put_float(buf, 24, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); #else mavlink_local_position_ned_system_global_offset_t packet; packet.time_boot_ms = time_boot_ms; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack( packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; - return mavlink_finalize_message(msg, system_id, component_id, 28, 231); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_ uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, x); _mav_put_float(buf, 8, y); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_ _mav_put_float(buf, 20, pitch); _mav_put_float(buf, 24, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); #else mavlink_local_position_ned_system_global_offset_t packet; packet.time_boot_ms = time_boot_ms; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_ packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 231); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encod static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, x); _mav_put_float(buf, 8, y); @@ -164,7 +175,11 @@ static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavl _mav_put_float(buf, 20, pitch); _mav_put_float(buf, 24, yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, 28, 231); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif #else mavlink_local_position_ned_system_global_offset_t packet; packet.time_boot_ms = time_boot_ms; @@ -175,7 +190,11 @@ static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavl packet.pitch = pitch; packet.yaw = yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, 28, 231); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_local_position_ned_system_global_offset_decode(co local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg); local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg); #else - memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), 28); + memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h index 9ab87d0dafc2b7f16e826fb7f9fc04ed0d52a626..96f35fe625c4761ab61b7c2fbee00ec8e98abfa8 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h @@ -14,6 +14,9 @@ typedef struct __mavlink_local_position_setpoint_t #define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17 #define MAVLINK_MSG_ID_51_LEN 17 +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC 223 +#define MAVLINK_MSG_ID_51_CRC 223 + #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i uint8_t coordinate_frame, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[17]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); _mav_put_uint8_t(buf, 16, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); #else mavlink_local_position_setpoint_t packet; packet.x = x; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 17, 223); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys uint8_t coordinate_frame,float x,float y,float z,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[17]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); _mav_put_uint8_t(buf, 16, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); #else mavlink_local_position_setpoint_t packet; packet.x = x; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 223); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[17]; + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); _mav_put_uint8_t(buf, 16, coordinate_frame); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 17, 223); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); +#endif #else mavlink_local_position_setpoint_t packet; packet.x = x; @@ -153,7 +168,11 @@ static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t ch packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 17, 223); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_mess local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg); #else - memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 17); + memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h index 96b3d3040ca7fbc790a797486ef26c150d4fe942..c9e4a4f8a59748563cf92bf287bbd4c9860c9e3a 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h @@ -15,6 +15,9 @@ typedef struct __mavlink_manual_control_t #define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 #define MAVLINK_MSG_ID_69_LEN 11 +#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 +#define MAVLINK_MSG_ID_69_CRC 243 + #define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_ uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[11]; + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; _mav_put_int16_t(buf, 0, x); _mav_put_int16_t(buf, 2, y); _mav_put_int16_t(buf, 4, z); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_ _mav_put_uint16_t(buf, 8, buttons); _mav_put_uint8_t(buf, 10, target); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); #else mavlink_manual_control_t packet; packet.x = x; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_ packet.buttons = buttons; packet.target = target; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 11, 243); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, u uint8_t target,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[11]; + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; _mav_put_int16_t(buf, 0, x); _mav_put_int16_t(buf, 2, y); _mav_put_int16_t(buf, 4, z); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, u _mav_put_uint16_t(buf, 8, buttons); _mav_put_uint8_t(buf, 10, target); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); #else mavlink_manual_control_t packet; packet.x = x; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, u packet.buttons = buttons; packet.target = target; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11, 243); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[11]; + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; _mav_put_int16_t(buf, 0, x); _mav_put_int16_t(buf, 2, y); _mav_put_int16_t(buf, 4, z); @@ -154,7 +165,11 @@ static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8 _mav_put_uint16_t(buf, 8, buttons); _mav_put_uint8_t(buf, 10, target); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, 11, 243); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif #else mavlink_manual_control_t packet; packet.x = x; @@ -164,7 +179,11 @@ static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8 packet.buttons = buttons; packet.target = target; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, 11, 243); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* ms manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); manual_control->target = mavlink_msg_manual_control_get_target(msg); #else - memcpy(manual_control, _MAV_PAYLOAD(msg), 11); + memcpy(manual_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h index 71db380a1a1259ca581e3570ffaa4190d7b12a29..d59e212921c6494a6571c1241bc1f9ace13b36bf 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h @@ -16,6 +16,9 @@ typedef struct __mavlink_manual_setpoint_t #define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 #define MAVLINK_MSG_ID_81_LEN 22 +#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 +#define MAVLINK_MSG_ID_81_CRC 106 + #define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8 uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 20, mode_switch); _mav_put_uint8_t(buf, 21, manual_override_switch); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); #else mavlink_manual_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8 packet.mode_switch = mode_switch; packet.manual_override_switch = manual_override_switch; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 22, 106); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 20, mode_switch); _mav_put_uint8_t(buf, 21, manual_override_switch); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); #else mavlink_manual_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, packet.mode_switch = mode_switch; packet.manual_override_switch = manual_override_switch; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 106); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uin static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); @@ -164,7 +175,11 @@ static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 20, mode_switch); _mav_put_uint8_t(buf, 21, manual_override_switch); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, 22, 106); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif #else mavlink_manual_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -175,7 +190,11 @@ static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint packet.mode_switch = mode_switch; packet.manual_override_switch = manual_override_switch; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, 22, 106); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* m manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg); manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg); #else - memcpy(manual_setpoint, _MAV_PAYLOAD(msg), 22); + memcpy(manual_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h index a61c13019be3146d5b4a87e03dadefa19f35b5c7..f8ae21b05cbe8fbd830ce48f7b61d0cda5ed245b 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h @@ -13,6 +13,9 @@ typedef struct __mavlink_memory_vect_t #define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 #define MAVLINK_MSG_ID_249_LEN 36 +#define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 +#define MAVLINK_MSG_ID_249_CRC 204 + #define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 #define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ @@ -42,23 +45,27 @@ static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t c uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; _mav_put_uint16_t(buf, 0, address); _mav_put_uint8_t(buf, 2, ver); _mav_put_uint8_t(buf, 3, type); _mav_put_int8_t_array(buf, 4, value, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); #else mavlink_memory_vect_t packet; packet.address = address; packet.ver = ver; packet.type = type; mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; - return mavlink_finalize_message(msg, system_id, component_id, 36, 204); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif } /** @@ -78,23 +85,27 @@ static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; _mav_put_uint16_t(buf, 0, address); _mav_put_uint8_t(buf, 2, ver); _mav_put_uint8_t(buf, 3, type); _mav_put_int8_t_array(buf, 4, value, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); #else mavlink_memory_vect_t packet; packet.address = address; packet.ver = ver; packet.type = type; mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 204); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif } /** @@ -124,19 +135,27 @@ static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; _mav_put_uint16_t(buf, 0, address); _mav_put_uint8_t(buf, 2, ver); _mav_put_uint8_t(buf, 3, type); _mav_put_int8_t_array(buf, 4, value, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, 36, 204); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif #else mavlink_memory_vect_t packet; packet.address = address; packet.ver = ver; packet.type = type; mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, 36, 204); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif #endif } @@ -199,6 +218,6 @@ static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, memory_vect->type = mavlink_msg_memory_vect_get_type(msg); mavlink_msg_memory_vect_get_value(msg, memory_vect->value); #else - memcpy(memory_vect, _MAV_PAYLOAD(msg), 36); + memcpy(memory_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMORY_VECT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h index 92eca79d1cb3947e3b743ca7d585d611c118a896..32825647f924bfcd05e3ef20725ec08583db5045 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h @@ -12,6 +12,9 @@ typedef struct __mavlink_mission_ack_t #define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 #define MAVLINK_MSG_ID_47_LEN 3 +#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 +#define MAVLINK_MSG_ID_47_CRC 153 + #define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c uint8_t target_system, uint8_t target_component, uint8_t type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, type); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); #else mavlink_mission_ack_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.type = type; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 3, 153); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint uint8_t target_system,uint8_t target_component,uint8_t type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, type); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); #else mavlink_mission_ack_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.type = type; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 153); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, type); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, 3, 153); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif #else mavlink_mission_ack_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.type = type; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, 3, 153); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); mission_ack->type = mavlink_msg_mission_ack_get_type(msg); #else - memcpy(mission_ack, _MAV_PAYLOAD(msg), 3); + memcpy(mission_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h index 602852f7e32946b6ae24718745befaeaf6886aca..06d2ac2e7976fcd755a0b5b7ed1dad456531d9fa 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h @@ -11,6 +11,9 @@ typedef struct __mavlink_mission_clear_all_t #define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 #define MAVLINK_MSG_ID_45_LEN 2 +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 +#define MAVLINK_MSG_ID_45_CRC 232 + #define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uin uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); #else mavlink_mission_clear_all_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; - return mavlink_finalize_message(msg, system_id, component_id, 2, 232); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id uint8_t target_system,uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); #else mavlink_mission_clear_all_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 232); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, u static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, 2, 232); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif #else mavlink_mission_clear_all_t packet; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, 2, 232); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); #else - memcpy(mission_clear_all, _MAV_PAYLOAD(msg), 2); + memcpy(mission_clear_all, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h index 61d8b221c31e17a15f06ae95f2c01f026cb08812..b28cec6f6d8ec23b2bdcc31aa323b750e0cb0ea1 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h @@ -12,6 +12,9 @@ typedef struct __mavlink_mission_count_t #define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 #define MAVLINK_MSG_ID_44_LEN 4 +#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 +#define MAVLINK_MSG_ID_44_CRC 221 + #define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t uint8_t target_system, uint8_t target_component, uint16_t count) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; _mav_put_uint16_t(buf, 0, count); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); #else mavlink_mission_count_t packet; packet.count = count; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; - return mavlink_finalize_message(msg, system_id, component_id, 4, 221); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, ui uint8_t target_system,uint8_t target_component,uint16_t count) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; _mav_put_uint16_t(buf, 0, count); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); #else mavlink_mission_count_t packet; packet.count = count; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 221); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8 static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; _mav_put_uint16_t(buf, 0, count); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, 4, 221); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif #else mavlink_mission_count_t packet; packet.count = count; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, 4, 221); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); #else - memcpy(mission_count, _MAV_PAYLOAD(msg), 4); + memcpy(mission_count, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_COUNT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h index 99370f83532bec328537f62bf72c327af6478d23..5bf0899beac5b85bab96dc56c737a10a9329942e 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h @@ -10,6 +10,9 @@ typedef struct __mavlink_mission_current_t #define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 #define MAVLINK_MSG_ID_42_LEN 2 +#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 +#define MAVLINK_MSG_ID_42_CRC 28 + #define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ @@ -33,19 +36,23 @@ static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8 uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); #else mavlink_mission_current_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; - return mavlink_finalize_message(msg, system_id, component_id, 2, 28); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif } /** @@ -62,19 +69,23 @@ static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); #else mavlink_mission_current_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 28); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif } /** @@ -101,15 +112,23 @@ static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uin static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; _mav_put_uint16_t(buf, 0, seq); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, 2, 28); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif #else mavlink_mission_current_t packet; packet.seq = seq; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, 2, 28); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif #endif } @@ -139,6 +158,6 @@ static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* m #if MAVLINK_NEED_BYTE_SWAP mission_current->seq = mavlink_msg_mission_current_get_seq(msg); #else - memcpy(mission_current, _MAV_PAYLOAD(msg), 2); + memcpy(mission_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CURRENT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h index d2c66d4daa293777c7732be1476014457ec7421d..ed9d6e4af71c3145a85831f669608644d0ee8c76 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h @@ -23,6 +23,9 @@ typedef struct __mavlink_mission_item_t #define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 #define MAVLINK_MSG_ID_39_LEN 37 +#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 +#define MAVLINK_MSG_ID_39_CRC 254 + #define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[37]; + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; _mav_put_float(buf, 0, param1); _mav_put_float(buf, 4, param2); _mav_put_float(buf, 8, param3); @@ -88,7 +91,7 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 35, current); _mav_put_uint8_t(buf, 36, autocontinue); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); #else mavlink_mission_item_t packet; packet.param1 = param1; @@ -106,11 +109,15 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t packet.current = current; packet.autocontinue = autocontinue; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; - return mavlink_finalize_message(msg, system_id, component_id, 37, 254); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif } /** @@ -140,7 +147,7 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[37]; + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; _mav_put_float(buf, 0, param1); _mav_put_float(buf, 4, param2); _mav_put_float(buf, 8, param3); @@ -156,7 +163,7 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 35, current); _mav_put_uint8_t(buf, 36, autocontinue); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); #else mavlink_mission_item_t packet; packet.param1 = param1; @@ -174,11 +181,15 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin packet.current = current; packet.autocontinue = autocontinue; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 37, 254); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif } /** @@ -218,7 +229,7 @@ static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[37]; + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; _mav_put_float(buf, 0, param1); _mav_put_float(buf, 4, param2); _mav_put_float(buf, 8, param3); @@ -234,7 +245,11 @@ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t _mav_put_uint8_t(buf, 35, current); _mav_put_uint8_t(buf, 36, autocontinue); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, 37, 254); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif #else mavlink_mission_item_t packet; packet.param1 = param1; @@ -252,7 +267,11 @@ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t packet.current = current; packet.autocontinue = autocontinue; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, 37, 254); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif #endif } @@ -425,6 +444,6 @@ static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mission_item->current = mavlink_msg_mission_item_get_current(msg); mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); #else - memcpy(mission_item, _MAV_PAYLOAD(msg), 37); + memcpy(mission_item, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h index 171f9857e8257c9b3b4ffec67e9a52aa0b006d38..3f8a51a13485abd25dabc9b9ac306e0fb8a29ca2 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h @@ -10,6 +10,9 @@ typedef struct __mavlink_mission_item_reached_t #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 #define MAVLINK_MSG_ID_46_LEN 2 +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 +#define MAVLINK_MSG_ID_46_CRC 11 + #define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ @@ -33,19 +36,23 @@ static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); #else mavlink_mission_item_reached_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; - return mavlink_finalize_message(msg, system_id, component_id, 2, 11); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif } /** @@ -62,19 +69,23 @@ static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); #else mavlink_mission_item_reached_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 11); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif } /** @@ -101,15 +112,23 @@ static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; _mav_put_uint16_t(buf, 0, seq); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, 2, 11); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif #else mavlink_mission_item_reached_t packet; packet.seq = seq; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, 2, 11); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif #endif } @@ -139,6 +158,6 @@ static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message #if MAVLINK_NEED_BYTE_SWAP mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); #else - memcpy(mission_item_reached, _MAV_PAYLOAD(msg), 2); + memcpy(mission_item_reached, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h index cde0a0cfb9b6b6d2967c8b5b200ec914106323e1..0ced17614e7e83e4bde1633e5a58c7d2bc30f314 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h @@ -12,6 +12,9 @@ typedef struct __mavlink_mission_request_t #define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 #define MAVLINK_MSG_ID_40_LEN 4 +#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 +#define MAVLINK_MSG_ID_40_CRC 230 + #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8 uint8_t target_system, uint8_t target_component, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; _mav_put_uint16_t(buf, 0, seq); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); #else mavlink_mission_request_t packet; packet.seq = seq; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, 4, 230); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t target_system,uint8_t target_component,uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; _mav_put_uint16_t(buf, 0, seq); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); #else mavlink_mission_request_t packet; packet.seq = seq; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 230); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uin static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; _mav_put_uint16_t(buf, 0, seq); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, 4, 230); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif #else mavlink_mission_request_t packet; packet.seq = seq; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, 4, 230); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* m mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); #else - memcpy(mission_request, _MAV_PAYLOAD(msg), 4); + memcpy(mission_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h index 1ada635b557cac3520c0d2447d638a9e9c88eb3b..391df7f4daace3d29ad6982894265352284443f2 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h @@ -11,6 +11,9 @@ typedef struct __mavlink_mission_request_list_t #define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 #define MAVLINK_MSG_ID_43_LEN 2 +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 +#define MAVLINK_MSG_ID_43_CRC 132 + #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); #else mavlink_mission_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, 2, 132); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system uint8_t target_system,uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); #else mavlink_mission_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 132); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, 2, 132); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif #else mavlink_mission_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, 2, 132); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_mission_request_list_decode(const mavlink_message mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); #else - memcpy(mission_request_list, _MAV_PAYLOAD(msg), 2); + memcpy(mission_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h index 76fd43befad147174cece9d8968ce33d0d29c0b5..d5a1c69397362af4793617b17ca1b11100ff4f81 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h @@ -13,6 +13,9 @@ typedef struct __mavlink_mission_request_partial_list_t #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 #define MAVLINK_MSG_ID_37_LEN 6 +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 +#define MAVLINK_MSG_ID_37_CRC 212 + #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; _mav_put_int16_t(buf, 0, start_index); _mav_put_int16_t(buf, 2, end_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); #else mavlink_mission_request_partial_list_t packet; packet.start_index = start_index; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; - return mavlink_finalize_message(msg, system_id, component_id, 6, 212); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_ uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; _mav_put_int16_t(buf, 0, start_index); _mav_put_int16_t(buf, 2, end_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); #else mavlink_mission_request_partial_list_t packet; packet.start_index = start_index; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_ packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 212); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t s static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; _mav_put_int16_t(buf, 0, start_index); _mav_put_int16_t(buf, 2, end_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, 6, 212); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif #else mavlink_mission_request_partial_list_t packet; packet.start_index = start_index; @@ -142,7 +157,11 @@ static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, 6, 212); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg); mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg); #else - memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), 6); + memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h index de0dbcd75df3b3dd029eab93d34eae24be90b882..2e145aa3e997c7c17383f98a6ebc958cff74b696 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h @@ -12,6 +12,9 @@ typedef struct __mavlink_mission_set_current_t #define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 #define MAVLINK_MSG_ID_41_LEN 4 +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 +#define MAVLINK_MSG_ID_41_CRC 28 + #define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, u uint8_t target_system, uint8_t target_component, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; _mav_put_uint16_t(buf, 0, seq); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); #else mavlink_mission_set_current_t packet; packet.seq = seq; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; - return mavlink_finalize_message(msg, system_id, component_id, 4, 28); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_ uint8_t target_system,uint8_t target_component,uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; _mav_put_uint16_t(buf, 0, seq); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); #else mavlink_mission_set_current_t packet; packet.seq = seq; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 28); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; _mav_put_uint16_t(buf, 0, seq); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, 4, 28); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif #else mavlink_mission_set_current_t packet; packet.seq = seq; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, 4, 28); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_ mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); #else - memcpy(mission_set_current, _MAV_PAYLOAD(msg), 4); + memcpy(mission_set_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h index 0e77569cfc3aecc3b0de720459d8ba94359386ac..6342f60383c82824bfd1e8004de200e9392c4043 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h @@ -13,6 +13,9 @@ typedef struct __mavlink_mission_write_partial_list_t #define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 #define MAVLINK_MSG_ID_38_LEN 6 +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 +#define MAVLINK_MSG_ID_38_CRC 9 + #define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; _mav_put_int16_t(buf, 0, start_index); _mav_put_int16_t(buf, 2, end_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); #else mavlink_mission_write_partial_list_t packet; packet.start_index = start_index; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; - return mavlink_finalize_message(msg, system_id, component_id, 6, 9); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; _mav_put_int16_t(buf, 0, start_index); _mav_put_int16_t(buf, 2, end_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); #else mavlink_mission_write_partial_list_t packet; packet.start_index = start_index; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 9); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t sys static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; _mav_put_int16_t(buf, 0, start_index); _mav_put_int16_t(buf, 2, end_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, 6, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif #else mavlink_mission_write_partial_list_t packet; packet.start_index = start_index; @@ -142,7 +157,11 @@ static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, 6, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_m mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg); mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg); #else - memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), 6); + memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h index 23a819e2c9b708ba1c4d004d8902edc1d155b121..a9d28a3d05a88c59275954cebdfb49878a756eb6 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h @@ -12,6 +12,9 @@ typedef struct __mavlink_named_value_float_t #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 #define MAVLINK_MSG_ID_251_LEN 18 +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 +#define MAVLINK_MSG_ID_251_CRC 170 + #define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 #define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uin uint32_t time_boot_ms, const char *name, float value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, value); _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); #else mavlink_named_value_float_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; - return mavlink_finalize_message(msg, system_id, component_id, 18, 170); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id uint32_t time_boot_ms,const char *name,float value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, value); _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); #else mavlink_named_value_float_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 170); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, u static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, value); _mav_put_char_array(buf, 8, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, 18, 170); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif #else mavlink_named_value_float_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, 18, 170); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* named_value_float->value = mavlink_msg_named_value_float_get_value(msg); mavlink_msg_named_value_float_get_name(msg, named_value_float->name); #else - memcpy(named_value_float, _MAV_PAYLOAD(msg), 18); + memcpy(named_value_float, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h index 3c67dff03fcbab7f855653fc23327d273dbca91f..ea53ea888d2cfa824a597a01c85bdd5805bc71a0 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h @@ -12,6 +12,9 @@ typedef struct __mavlink_named_value_int_t #define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 #define MAVLINK_MSG_ID_252_LEN 18 +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 +#define MAVLINK_MSG_ID_252_CRC 44 + #define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 #define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ @@ -39,21 +42,25 @@ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8 uint32_t time_boot_ms, const char *name, int32_t value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, value); _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); #else mavlink_named_value_int_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; - return mavlink_finalize_message(msg, system_id, component_id, 18, 44); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif } /** @@ -72,21 +79,25 @@ static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint32_t time_boot_ms,const char *name,int32_t value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, value); _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); #else mavlink_named_value_int_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 44); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif } /** @@ -115,17 +126,25 @@ static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uin static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, value); _mav_put_char_array(buf, 8, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, 18, 44); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif #else mavlink_named_value_int_t packet; packet.time_boot_ms = time_boot_ms; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, 18, 44); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif #endif } @@ -177,6 +196,6 @@ static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* m named_value_int->value = mavlink_msg_named_value_int_get_value(msg); mavlink_msg_named_value_int_get_name(msg, named_value_int->name); #else - memcpy(named_value_int, _MAV_PAYLOAD(msg), 18); + memcpy(named_value_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h index 028afdabc62203d7d0e7427ef6e093c1b7088741..e9fa0f522008dc5fcb91008bd043d780ea5df9bf 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h @@ -17,6 +17,9 @@ typedef struct __mavlink_nav_controller_output_t #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 #define MAVLINK_MSG_ID_62_LEN 26 +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 +#define MAVLINK_MSG_ID_62_CRC 183 + #define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ @@ -54,7 +57,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; _mav_put_float(buf, 0, nav_roll); _mav_put_float(buf, 4, nav_pitch); _mav_put_float(buf, 8, alt_error); @@ -64,7 +67,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, _mav_put_int16_t(buf, 22, target_bearing); _mav_put_uint16_t(buf, 24, wp_dist); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); #else mavlink_nav_controller_output_t packet; packet.nav_roll = nav_roll; @@ -76,11 +79,15 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, packet.target_bearing = target_bearing; packet.wp_dist = wp_dist; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; - return mavlink_finalize_message(msg, system_id, component_id, 26, 183); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif } /** @@ -104,7 +111,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; _mav_put_float(buf, 0, nav_roll); _mav_put_float(buf, 4, nav_pitch); _mav_put_float(buf, 8, alt_error); @@ -114,7 +121,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste _mav_put_int16_t(buf, 22, target_bearing); _mav_put_uint16_t(buf, 24, wp_dist); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); #else mavlink_nav_controller_output_t packet; packet.nav_roll = nav_roll; @@ -126,11 +133,15 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste packet.target_bearing = target_bearing; packet.wp_dist = wp_dist; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 183); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif } /** @@ -164,7 +175,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_i static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; _mav_put_float(buf, 0, nav_roll); _mav_put_float(buf, 4, nav_pitch); _mav_put_float(buf, 8, alt_error); @@ -174,7 +185,11 @@ static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan _mav_put_int16_t(buf, 22, target_bearing); _mav_put_uint16_t(buf, 24, wp_dist); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, 26, 183); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif #else mavlink_nav_controller_output_t packet; packet.nav_roll = nav_roll; @@ -186,7 +201,11 @@ static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan packet.target_bearing = target_bearing; packet.wp_dist = wp_dist; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, 26, 183); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif #endif } @@ -293,6 +312,6 @@ static inline void mavlink_msg_nav_controller_output_decode(const mavlink_messag nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); #else - memcpy(nav_controller_output, _MAV_PAYLOAD(msg), 26); + memcpy(nav_controller_output, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h index 9bb1e336972c231ec225f069917fb55c9f94fb1d..c0e765a444fd9816edbaef3d9b90fd37e5502f50 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h @@ -15,6 +15,9 @@ typedef struct __mavlink_omnidirectional_flow_t #define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54 #define MAVLINK_MSG_ID_106_LEN 54 +#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211 +#define MAVLINK_MSG_ID_106_CRC 211 + #define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_LEFT_LEN 10 #define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_RIGHT_LEN 10 @@ -49,14 +52,14 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[54]; + char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, front_distance_m); _mav_put_uint8_t(buf, 52, sensor_id); _mav_put_uint8_t(buf, 53, quality); _mav_put_int16_t_array(buf, 12, left, 10); _mav_put_int16_t_array(buf, 32, right, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); #else mavlink_omnidirectional_flow_t packet; packet.time_usec = time_usec; @@ -65,11 +68,15 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id, packet.quality = quality; mav_array_memcpy(packet.left, left, sizeof(int16_t)*10); mav_array_memcpy(packet.right, right, sizeof(int16_t)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, 54, 211); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); +#endif } /** @@ -91,14 +98,14 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system uint64_t time_usec,uint8_t sensor_id,const int16_t *left,const int16_t *right,uint8_t quality,float front_distance_m) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[54]; + char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, front_distance_m); _mav_put_uint8_t(buf, 52, sensor_id); _mav_put_uint8_t(buf, 53, quality); _mav_put_int16_t_array(buf, 12, left, 10); _mav_put_int16_t_array(buf, 32, right, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); #else mavlink_omnidirectional_flow_t packet; packet.time_usec = time_usec; @@ -107,11 +114,15 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system packet.quality = quality; mav_array_memcpy(packet.left, left, sizeof(int16_t)*10); mav_array_memcpy(packet.right, right, sizeof(int16_t)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 54, 211); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); +#endif } /** @@ -143,14 +154,18 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[54]; + char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, front_distance_m); _mav_put_uint8_t(buf, 52, sensor_id); _mav_put_uint8_t(buf, 53, quality); _mav_put_int16_t_array(buf, 12, left, 10); _mav_put_int16_t_array(buf, 32, right, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, 54, 211); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); +#endif #else mavlink_omnidirectional_flow_t packet; packet.time_usec = time_usec; @@ -159,7 +174,11 @@ static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan, packet.quality = quality; mav_array_memcpy(packet.left, left, sizeof(int16_t)*10); mav_array_memcpy(packet.right, right, sizeof(int16_t)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, 54, 211); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); +#endif #endif } @@ -244,6 +263,6 @@ static inline void mavlink_msg_omnidirectional_flow_decode(const mavlink_message omnidirectional_flow->sensor_id = mavlink_msg_omnidirectional_flow_get_sensor_id(msg); omnidirectional_flow->quality = mavlink_msg_omnidirectional_flow_get_quality(msg); #else - memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), 54); + memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h index b277cab5124965b179ed0c13c570954811d02ea1..e01dc5e79cf8bfcd62e51e7303c7c54420ae7a5d 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h @@ -17,6 +17,9 @@ typedef struct __mavlink_optical_flow_t #define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 #define MAVLINK_MSG_ID_100_LEN 26 +#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 +#define MAVLINK_MSG_ID_100_CRC 175 + #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ @@ -54,7 +57,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, flow_comp_m_x); _mav_put_float(buf, 12, flow_comp_m_y); @@ -64,7 +67,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 24, sensor_id); _mav_put_uint8_t(buf, 25, quality); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); #else mavlink_optical_flow_t packet; packet.time_usec = time_usec; @@ -76,11 +79,15 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t packet.sensor_id = sensor_id; packet.quality = quality; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, 26, 175); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif } /** @@ -104,7 +111,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, flow_comp_m_x); _mav_put_float(buf, 12, flow_comp_m_y); @@ -114,7 +121,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 24, sensor_id); _mav_put_uint8_t(buf, 25, quality); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); #else mavlink_optical_flow_t packet; packet.time_usec = time_usec; @@ -126,11 +133,15 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin packet.sensor_id = sensor_id; packet.quality = quality; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 175); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif } /** @@ -164,7 +175,7 @@ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_float(buf, 8, flow_comp_m_x); _mav_put_float(buf, 12, flow_comp_m_y); @@ -174,7 +185,11 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_ _mav_put_uint8_t(buf, 24, sensor_id); _mav_put_uint8_t(buf, 25, quality); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 26, 175); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif #else mavlink_optical_flow_t packet; packet.time_usec = time_usec; @@ -186,7 +201,11 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_ packet.sensor_id = sensor_id; packet.quality = quality; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 26, 175); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif #endif } @@ -293,6 +312,6 @@ static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); #else - memcpy(optical_flow, _MAV_PAYLOAD(msg), 26); + memcpy(optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h index 125df80c85d7711c749e8f35ee7ea0366c9129e6..da61181b2c9e009c1293690f4d6c0a02c61f7dcc 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h @@ -11,6 +11,9 @@ typedef struct __mavlink_param_request_list_t #define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 #define MAVLINK_MSG_ID_21_LEN 2 +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 +#define MAVLINK_MSG_ID_21_CRC 159 + #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, ui uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); #else mavlink_param_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, 2, 159); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_i uint8_t target_system,uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); #else mavlink_param_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 159); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, 2, 159); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif #else mavlink_param_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, 2, 159); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); #else - memcpy(param_request_list, _MAV_PAYLOAD(msg), 2); + memcpy(param_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h index dba528df97d392c28f1686fe2008f564b913025c..6b156802609e9648d45f3bea7b722a5d72f39ca3 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h @@ -13,6 +13,9 @@ typedef struct __mavlink_param_request_read_t #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 #define MAVLINK_MSG_ID_20_LEN 20 +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 +#define MAVLINK_MSG_ID_20_CRC 214 + #define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ @@ -42,23 +45,27 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; _mav_put_int16_t(buf, 0, param_index); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); #else mavlink_param_request_read_t packet; packet.param_index = param_index; packet.target_system = target_system; packet.target_component = target_component; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; - return mavlink_finalize_message(msg, system_id, component_id, 20, 214); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif } /** @@ -78,23 +85,27 @@ static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_i uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; _mav_put_int16_t(buf, 0, param_index); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); #else mavlink_param_request_read_t packet; packet.param_index = param_index; packet.target_system = target_system; packet.target_component = target_component; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 214); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif } /** @@ -124,19 +135,27 @@ static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; _mav_put_int16_t(buf, 0, param_index); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); _mav_put_char_array(buf, 4, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, 20, 214); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif #else mavlink_param_request_read_t packet; packet.param_index = param_index; packet.target_system = target_system; packet.target_component = target_component; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, 20, 214); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif #endif } @@ -199,6 +218,6 @@ static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); #else - memcpy(param_request_read, _MAV_PAYLOAD(msg), 20); + memcpy(param_request_read, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h index 8f00f22e9db97cbfdc2a0693353fa26d324c41d7..66b0f6629b8b664dcc2c878d058d94d09a9d4107 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h @@ -14,6 +14,9 @@ typedef struct __mavlink_param_set_t #define MAVLINK_MSG_ID_PARAM_SET_LEN 23 #define MAVLINK_MSG_ID_23_LEN 23 +#define MAVLINK_MSG_ID_PARAM_SET_CRC 168 +#define MAVLINK_MSG_ID_23_CRC 168 + #define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 #define MAVLINK_MESSAGE_INFO_PARAM_SET { \ @@ -45,13 +48,13 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[23]; + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; _mav_put_float(buf, 0, param_value); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); _mav_put_uint8_t(buf, 22, param_type); _mav_put_char_array(buf, 6, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); #else mavlink_param_set_t packet; packet.param_value = param_value; @@ -59,11 +62,15 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com packet.target_component = target_component; packet.param_type = param_type; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_SET; - return mavlink_finalize_message(msg, system_id, component_id, 23, 168); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif } /** @@ -84,13 +91,13 @@ static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_ uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[23]; + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; _mav_put_float(buf, 0, param_value); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); _mav_put_uint8_t(buf, 22, param_type); _mav_put_char_array(buf, 6, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); #else mavlink_param_set_t packet; packet.param_value = param_value; @@ -98,11 +105,15 @@ static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_ packet.target_component = target_component; packet.param_type = param_type; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_SET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 23, 168); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif } /** @@ -133,13 +144,17 @@ static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t c static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[23]; + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; _mav_put_float(buf, 0, param_value); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); _mav_put_uint8_t(buf, 22, param_type); _mav_put_char_array(buf, 6, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, 23, 168); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif #else mavlink_param_set_t packet; packet.param_value = param_value; @@ -147,7 +162,11 @@ static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t ta packet.target_component = target_component; packet.param_type = param_type; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, 23, 168); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif #endif } @@ -221,6 +240,6 @@ static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, ma mavlink_msg_param_set_get_param_id(msg, param_set->param_id); param_set->param_type = mavlink_msg_param_set_get_param_type(msg); #else - memcpy(param_set, _MAV_PAYLOAD(msg), 23); + memcpy(param_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_SET_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h index 03a631984393194911296c94664ca644089ee3dd..5991393746f17c1c2d6cf6fb4e73c305b50e198e 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h @@ -14,6 +14,9 @@ typedef struct __mavlink_param_value_t #define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 #define MAVLINK_MSG_ID_22_LEN 25 +#define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 +#define MAVLINK_MSG_ID_22_CRC 220 + #define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 #define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ @@ -45,13 +48,13 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; _mav_put_float(buf, 0, param_value); _mav_put_uint16_t(buf, 4, param_count); _mav_put_uint16_t(buf, 6, param_index); _mav_put_uint8_t(buf, 24, param_type); _mav_put_char_array(buf, 8, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); #else mavlink_param_value_t packet; packet.param_value = param_value; @@ -59,11 +62,15 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c packet.param_index = param_index; packet.param_type = param_type; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; - return mavlink_finalize_message(msg, system_id, component_id, 25, 220); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif } /** @@ -84,13 +91,13 @@ static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; _mav_put_float(buf, 0, param_value); _mav_put_uint16_t(buf, 4, param_count); _mav_put_uint16_t(buf, 6, param_index); _mav_put_uint8_t(buf, 24, param_type); _mav_put_char_array(buf, 8, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); #else mavlink_param_value_t packet; packet.param_value = param_value; @@ -98,11 +105,15 @@ static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint packet.param_index = param_index; packet.param_type = param_type; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 220); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif } /** @@ -133,13 +144,17 @@ static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; _mav_put_float(buf, 0, param_value); _mav_put_uint16_t(buf, 4, param_count); _mav_put_uint16_t(buf, 6, param_index); _mav_put_uint8_t(buf, 24, param_type); _mav_put_char_array(buf, 8, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, 25, 220); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif #else mavlink_param_value_t packet; packet.param_value = param_value; @@ -147,7 +162,11 @@ static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const ch packet.param_index = param_index; packet.param_type = param_type; mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, 25, 220); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif #endif } @@ -221,6 +240,6 @@ static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_msg_param_value_get_param_id(msg, param_value->param_id); param_value->param_type = mavlink_msg_param_value_get_param_type(msg); #else - memcpy(param_value, _MAV_PAYLOAD(msg), 25); + memcpy(param_value, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_VALUE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h index 3ed1b9d7c46d07c46d1fb60d62a8feefed4c5b87..5a4c50907de6d47f89f2aeb43a7bc10dd36ff2d3 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h @@ -13,6 +13,9 @@ typedef struct __mavlink_ping_t #define MAVLINK_MSG_ID_PING_LEN 14 #define MAVLINK_MSG_ID_4_LEN 14 +#define MAVLINK_MSG_ID_PING_CRC 237 +#define MAVLINK_MSG_ID_4_CRC 237 + #define MAVLINK_MESSAGE_INFO_PING { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_PING_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_uint32_t(buf, 8, seq); _mav_put_uint8_t(buf, 12, target_system); _mav_put_uint8_t(buf, 13, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); #else mavlink_ping_t packet; packet.time_usec = time_usec; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PING; - return mavlink_finalize_message(msg, system_id, component_id, 14, 237); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t com uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_PING_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_uint32_t(buf, 8, seq); _mav_put_uint8_t(buf, 12, target_system); _mav_put_uint8_t(buf, 13, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); #else mavlink_ping_t packet; packet.time_usec = time_usec; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t com packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PING; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 237); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t compon static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_PING_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_uint32_t(buf, 8, seq); _mav_put_uint8_t(buf, 12, target_system); _mav_put_uint8_t(buf, 13, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, 14, 237); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); +#endif #else mavlink_ping_t packet; packet.time_usec = time_usec; @@ -142,7 +157,11 @@ static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_u packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, 14, 237); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink ping->target_system = mavlink_msg_ping_get_target_system(msg); ping->target_component = mavlink_msg_ping_get_target_component(msg); #else - memcpy(ping, _MAV_PAYLOAD(msg), 14); + memcpy(ping, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PING_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h new file mode 100644 index 0000000000000000000000000000000000000000..06e6a55425586a85f70fdb276d83403256fc7915 --- /dev/null +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h @@ -0,0 +1,295 @@ +// MESSAGE RADIO_STATUS PACKING + +#define MAVLINK_MSG_ID_RADIO_STATUS 109 + +typedef struct __mavlink_radio_status_t +{ + uint16_t rxerrors; ///< receive errors + uint16_t fixed; ///< count of error corrected packets + uint8_t rssi; ///< local signal strength + uint8_t remrssi; ///< remote signal strength + uint8_t txbuf; ///< how full the tx buffer is as a percentage + uint8_t noise; ///< background noise level + uint8_t remnoise; ///< remote background noise level +} mavlink_radio_status_t; + +#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 +#define MAVLINK_MSG_ID_109_LEN 9 + +#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 +#define MAVLINK_MSG_ID_109_CRC 185 + + + +#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ + "RADIO_STATUS", \ + 7, \ + { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ + { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ + { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ + { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ + { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ + } \ +} + + +/** + * @brief Pack a radio_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 rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} + +/** + * @brief Pack a radio_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} + +/** + * @brief Encode a radio_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 radio_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) +{ + return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); +} + +/** + * @brief Send a radio_status message + * @param chan MAVLink channel to send the message + * + * @param rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_status_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#endif +} + +#endif + +// MESSAGE RADIO_STATUS UNPACKING + + +/** + * @brief Get field rssi from radio_status message + * + * @return local signal strength + */ +static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field remrssi from radio_status message + * + * @return remote signal strength + */ +static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field txbuf from radio_status message + * + * @return how full the tx buffer is as a percentage + */ +static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field noise from radio_status message + * + * @return background noise level + */ +static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field remnoise from radio_status message + * + * @return remote background noise level + */ +static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field rxerrors from radio_status message + * + * @return receive errors + */ +static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field fixed from radio_status message + * + * @return count of error corrected packets + */ +static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a radio_status message into a struct + * + * @param msg The message to decode + * @param radio_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_status_decode(const mavlink_message_t* msg, mavlink_radio_status_t* radio_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + radio_status->rxerrors = mavlink_msg_radio_status_get_rxerrors(msg); + radio_status->fixed = mavlink_msg_radio_status_get_fixed(msg); + radio_status->rssi = mavlink_msg_radio_status_get_rssi(msg); + radio_status->remrssi = mavlink_msg_radio_status_get_remrssi(msg); + radio_status->txbuf = mavlink_msg_radio_status_get_txbuf(msg); + radio_status->noise = mavlink_msg_radio_status_get_noise(msg); + radio_status->remnoise = mavlink_msg_radio_status_get_remnoise(msg); +#else + memcpy(radio_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h index 1c1d4838867498580bad0031f86f7dfe21ece77c..ce88636473d4131d20e3ea26d53b78dbf2cdefe4 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h @@ -19,6 +19,9 @@ typedef struct __mavlink_raw_imu_t #define MAVLINK_MSG_ID_RAW_IMU_LEN 26 #define MAVLINK_MSG_ID_27_LEN 26 +#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 +#define MAVLINK_MSG_ID_27_CRC 144 + #define MAVLINK_MESSAGE_INFO_RAW_IMU { \ @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int16_t(buf, 8, xacc); _mav_put_int16_t(buf, 10, yacc); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); #else mavlink_raw_imu_t packet; packet.time_usec = time_usec; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RAW_IMU; - return mavlink_finalize_message(msg, system_id, component_id, 26, 144); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif } /** @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int16_t(buf, 8, xacc); _mav_put_int16_t(buf, 10, yacc); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); #else mavlink_raw_imu_t packet; packet.time_usec = time_usec; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RAW_IMU; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 144); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif } /** @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int16_t(buf, 8, xacc); _mav_put_int16_t(buf, 10, yacc); @@ -194,7 +205,11 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t tim _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, 26, 144); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif #else mavlink_raw_imu_t packet; packet.time_usec = time_usec; @@ -208,7 +223,11 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t tim packet.ymag = ymag; packet.zmag = zmag; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, 26, 144); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif #endif } @@ -337,6 +356,6 @@ static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavl raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); #else - memcpy(raw_imu, _MAV_PAYLOAD(msg), 26); + memcpy(raw_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_IMU_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h index f3e4e8404660a8215439d1fc345c58838117b029..dcc2cbe063ff22063e2cc51bf1870b26a593eeb6 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h @@ -14,6 +14,9 @@ typedef struct __mavlink_raw_pressure_t #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 #define MAVLINK_MSG_ID_28_LEN 16 +#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 +#define MAVLINK_MSG_ID_28_CRC 67 + #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int16_t(buf, 8, press_abs); _mav_put_int16_t(buf, 10, press_diff1); _mav_put_int16_t(buf, 12, press_diff2); _mav_put_int16_t(buf, 14, temperature); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); #else mavlink_raw_pressure_t packet; packet.time_usec = time_usec; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t packet.press_diff2 = press_diff2; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; - return mavlink_finalize_message(msg, system_id, component_id, 16, 67); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uin uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int16_t(buf, 8, press_abs); _mav_put_int16_t(buf, 10, press_diff1); _mav_put_int16_t(buf, 12, press_diff2); _mav_put_int16_t(buf, 14, temperature); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); #else mavlink_raw_pressure_t packet; packet.time_usec = time_usec; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uin packet.press_diff2 = press_diff2; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 67); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; _mav_put_uint64_t(buf, 0, time_usec); _mav_put_int16_t(buf, 8, press_abs); _mav_put_int16_t(buf, 10, press_diff1); _mav_put_int16_t(buf, 12, press_diff2); _mav_put_int16_t(buf, 14, temperature); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, 16, 67); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif #else mavlink_raw_pressure_t packet; packet.time_usec = time_usec; @@ -153,7 +168,11 @@ static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_ packet.press_diff2 = press_diff2; packet.temperature = temperature; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, 16, 67); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); #else - memcpy(raw_pressure, _MAV_PAYLOAD(msg), 16); + memcpy(raw_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_PRESSURE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h index d719c7fca2c357a74684382e9be28186513490d3..9854a190cebc67e777d0315d3c8659fadaf2b2c3 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h @@ -19,6 +19,9 @@ typedef struct __mavlink_rc_channels_override_t #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 #define MAVLINK_MSG_ID_70_LEN 18 +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 +#define MAVLINK_MSG_ID_70_CRC 124 + #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; _mav_put_uint16_t(buf, 0, chan1_raw); _mav_put_uint16_t(buf, 2, chan2_raw); _mav_put_uint16_t(buf, 4, chan3_raw); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); #else mavlink_rc_channels_override_t packet; packet.chan1_raw = chan1_raw; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; - return mavlink_finalize_message(msg, system_id, component_id, 18, 124); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif } /** @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; _mav_put_uint16_t(buf, 0, chan1_raw); _mav_put_uint16_t(buf, 2, chan2_raw); _mav_put_uint16_t(buf, 4, chan3_raw); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); #else mavlink_rc_channels_override_t packet; packet.chan1_raw = chan1_raw; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 124); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif } /** @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; _mav_put_uint16_t(buf, 0, chan1_raw); _mav_put_uint16_t(buf, 2, chan2_raw); _mav_put_uint16_t(buf, 4, chan3_raw); @@ -194,7 +205,11 @@ static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, 18, 124); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif #else mavlink_rc_channels_override_t packet; packet.chan1_raw = chan1_raw; @@ -208,7 +223,11 @@ static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, 18, 124); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif #endif } @@ -337,6 +356,6 @@ static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); #else - memcpy(rc_channels_override, _MAV_PAYLOAD(msg), 18); + memcpy(rc_channels_override, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h index a4d40da3806b375876c9e3067315044f8e9e44a7..4c1315bed22d0d1ccb1c5e5c8df2ad9d6fee43e7 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h @@ -20,6 +20,9 @@ typedef struct __mavlink_rc_channels_raw_t #define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 #define MAVLINK_MSG_ID_35_LEN 22 +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 +#define MAVLINK_MSG_ID_35_CRC 244 + #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8 uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_uint16_t(buf, 4, chan1_raw); _mav_put_uint16_t(buf, 6, chan2_raw); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 20, port); _mav_put_uint8_t(buf, 21, rssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); #else mavlink_rc_channels_raw_t packet; packet.time_boot_ms = time_boot_ms; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8 packet.port = port; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; - return mavlink_finalize_message(msg, system_id, component_id, 22, 244); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_uint16_t(buf, 4, chan1_raw); _mav_put_uint16_t(buf, 6, chan2_raw); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 20, port); _mav_put_uint8_t(buf, 21, rssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); #else mavlink_rc_channels_raw_t packet; packet.time_boot_ms = time_boot_ms; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, packet.port = port; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 244); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uin static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_uint16_t(buf, 4, chan1_raw); _mav_put_uint16_t(buf, 6, chan2_raw); @@ -204,7 +215,11 @@ static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 20, port); _mav_put_uint8_t(buf, 21, rssi); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, 22, 244); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif #else mavlink_rc_channels_raw_t packet; packet.time_boot_ms = time_boot_ms; @@ -219,7 +234,11 @@ static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint packet.port = port; packet.rssi = rssi; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, 22, 244); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* m rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); #else - memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), 22); + memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h index dd21d4162c057f41ba6a6ca7999b03552ffc1c31..be6322bcd3f3c602cda6a98296216a8c5dffad5f 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h @@ -20,6 +20,9 @@ typedef struct __mavlink_rc_channels_scaled_t #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 #define MAVLINK_MSG_ID_34_LEN 22 +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 +#define MAVLINK_MSG_ID_34_CRC 237 + #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, chan1_scaled); _mav_put_int16_t(buf, 6, chan2_scaled); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui _mav_put_uint8_t(buf, 20, port); _mav_put_uint8_t(buf, 21, rssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); #else mavlink_rc_channels_scaled_t packet; packet.time_boot_ms = time_boot_ms; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui packet.port = port; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; - return mavlink_finalize_message(msg, system_id, component_id, 22, 237); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, chan1_scaled); _mav_put_int16_t(buf, 6, chan2_scaled); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i _mav_put_uint8_t(buf, 20, port); _mav_put_uint8_t(buf, 21, rssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); #else mavlink_rc_channels_scaled_t packet; packet.time_boot_ms = time_boot_ms; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i packet.port = port; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 237); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, chan1_scaled); _mav_put_int16_t(buf, 6, chan2_scaled); @@ -204,7 +215,11 @@ static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, u _mav_put_uint8_t(buf, 20, port); _mav_put_uint8_t(buf, 21, rssi); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, 22, 237); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif #else mavlink_rc_channels_scaled_t packet; packet.time_boot_ms = time_boot_ms; @@ -219,7 +234,11 @@ static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, u packet.port = port; packet.rssi = rssi; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, 22, 237); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); #else - memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), 22); + memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h index d8653ad1095f292b744d72ea070d351bffa59bf9..ee21d1fe07b191cbda7e1ec6e4cf13437c8d41f5 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h @@ -14,6 +14,9 @@ typedef struct __mavlink_request_data_stream_t #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 #define MAVLINK_MSG_ID_66_LEN 6 +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 +#define MAVLINK_MSG_ID_66_CRC 148 + #define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; _mav_put_uint16_t(buf, 0, req_message_rate); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); _mav_put_uint8_t(buf, 4, req_stream_id); _mav_put_uint8_t(buf, 5, start_stop); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); #else mavlink_request_data_stream_t packet; packet.req_message_rate = req_message_rate; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u packet.req_stream_id = req_stream_id; packet.start_stop = start_stop; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); #endif msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; - return mavlink_finalize_message(msg, system_id, component_id, 6, 148); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_ uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; _mav_put_uint16_t(buf, 0, req_message_rate); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); _mav_put_uint8_t(buf, 4, req_stream_id); _mav_put_uint8_t(buf, 5, start_stop); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); #else mavlink_request_data_stream_t packet; packet.req_message_rate = req_message_rate; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_ packet.req_stream_id = req_stream_id; packet.start_stop = start_stop; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); #endif msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 148); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; _mav_put_uint16_t(buf, 0, req_message_rate); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); _mav_put_uint8_t(buf, 4, req_stream_id); _mav_put_uint8_t(buf, 5, start_stop); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, 6, 148); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif #else mavlink_request_data_stream_t packet; packet.req_message_rate = req_message_rate; @@ -153,7 +168,11 @@ static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, packet.req_stream_id = req_stream_id; packet.start_stop = start_stop; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, 6, 148); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_ request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); #else - memcpy(request_data_stream, _MAV_PAYLOAD(msg), 6); + memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h index 47772e004478a3e489ef5a2e45c572e9283e016a..a7e9df94be42a5ae92b82ccc5cc8857bbd790a8d 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h @@ -14,6 +14,9 @@ typedef struct __mavlink_roll_pitch_yaw_rates_thrust_setpoint_t #define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20 #define MAVLINK_MSG_ID_80_LEN 20 +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC 127 +#define MAVLINK_MSG_ID_80_CRC 127 + #define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uin uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll_rate); _mav_put_float(buf, 8, pitch_rate); _mav_put_float(buf, 12, yaw_rate); _mav_put_float(buf, 16, thrust); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); #else mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uin packet.yaw_rate = yaw_rate; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 20, 127); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_cha uint32_t time_boot_ms,float roll_rate,float pitch_rate,float yaw_rate,float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll_rate); _mav_put_float(buf, 8, pitch_rate); _mav_put_float(buf, 12, yaw_rate); _mav_put_float(buf, 16, thrust); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); #else mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_cha packet.yaw_rate = yaw_rate; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 127); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(u static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll_rate); _mav_put_float(buf, 8, pitch_rate); _mav_put_float(buf, 12, yaw_rate); _mav_put_float(buf, 16, thrust); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, 20, 127); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); +#endif #else mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -153,7 +168,11 @@ static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink packet.yaw_rate = yaw_rate; packet.thrust = thrust; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, 20, 127); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(const roll_pitch_yaw_rates_thrust_setpoint->yaw_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(msg); roll_pitch_yaw_rates_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(msg); #else - memcpy(roll_pitch_yaw_rates_thrust_setpoint, _MAV_PAYLOAD(msg), 20); + memcpy(roll_pitch_yaw_rates_thrust_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h index 5751badc3e2bde36cddcbb4de14a33f2a6335ba3..517797655ce353b3cdb00545bd0fa4c618e58f61 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h @@ -14,6 +14,9 @@ typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t #define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 #define MAVLINK_MSG_ID_59_LEN 20 +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC 238 +#define MAVLINK_MSG_ID_59_CRC 238 + #define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uin uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll_speed); _mav_put_float(buf, 8, pitch_speed); _mav_put_float(buf, 12, yaw_speed); _mav_put_float(buf, 16, thrust); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); #else mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uin packet.yaw_speed = yaw_speed; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 20, 238); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_cha uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll_speed); _mav_put_float(buf, 8, pitch_speed); _mav_put_float(buf, 12, yaw_speed); _mav_put_float(buf, 16, thrust); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); #else mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_cha packet.yaw_speed = yaw_speed; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 238); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(u static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll_speed); _mav_put_float(buf, 8, pitch_speed); _mav_put_float(buf, 12, yaw_speed); _mav_put_float(buf, 16, thrust); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, 20, 238); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); +#endif #else mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -153,7 +168,11 @@ static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink packet.yaw_speed = yaw_speed; packet.thrust = thrust; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, 20, 238); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg); roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg); #else - memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), 20); + memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h index a9f6ad0caa61a1fcfc9d951a0b52b7a5112ee826..aee036022b0abf15ddc177738119cee017f358f0 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h @@ -14,6 +14,9 @@ typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t #define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20 #define MAVLINK_MSG_ID_58_LEN 20 +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC 239 +#define MAVLINK_MSG_ID_58_CRC 239 + #define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t s uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); _mav_put_float(buf, 12, yaw); _mav_put_float(buf, 16, thrust); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); #else mavlink_roll_pitch_yaw_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t s packet.yaw = yaw; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 20, 239); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); _mav_put_float(buf, 12, yaw); _mav_put_float(buf, 16, thrust); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); #else mavlink_roll_pitch_yaw_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint packet.yaw = yaw; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 239); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, roll); _mav_put_float(buf, 8, pitch); _mav_put_float(buf, 12, yaw); _mav_put_float(buf, 16, thrust); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, 20, 239); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); +#endif #else mavlink_roll_pitch_yaw_thrust_setpoint_t packet; packet.time_boot_ms = time_boot_ms; @@ -153,7 +168,11 @@ static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_chann packet.yaw = yaw; packet.thrust = thrust; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, 20, 239); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavli roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg); roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg); #else - memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), 20); + memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h index aae6fd206ae9910aad8dd98ac000e67af3035b12..100fabf16eb340bd2a35a82bf340a982032c1db5 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h @@ -16,6 +16,9 @@ typedef struct __mavlink_safety_allowed_area_t #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 #define MAVLINK_MSG_ID_55_LEN 25 +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 +#define MAVLINK_MSG_ID_55_CRC 3 + #define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; _mav_put_float(buf, 0, p1x); _mav_put_float(buf, 4, p1y); _mav_put_float(buf, 8, p1z); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u _mav_put_float(buf, 20, p2z); _mav_put_uint8_t(buf, 24, frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); #else mavlink_safety_allowed_area_t packet; packet.p1x = p1x; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u packet.p2z = p2z; packet.frame = frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; - return mavlink_finalize_message(msg, system_id, component_id, 25, 3); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_ uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; _mav_put_float(buf, 0, p1x); _mav_put_float(buf, 4, p1y); _mav_put_float(buf, 8, p1z); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_ _mav_put_float(buf, 20, p2z); _mav_put_uint8_t(buf, 24, frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); #else mavlink_safety_allowed_area_t packet; packet.p1x = p1x; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_ packet.p2z = p2z; packet.frame = frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 3); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; _mav_put_float(buf, 0, p1x); _mav_put_float(buf, 4, p1y); _mav_put_float(buf, 8, p1z); @@ -164,7 +175,11 @@ static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, _mav_put_float(buf, 20, p2z); _mav_put_uint8_t(buf, 24, frame); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, 25, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif #else mavlink_safety_allowed_area_t packet; packet.p1x = p1x; @@ -175,7 +190,11 @@ static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, packet.p2z = p2z; packet.frame = frame; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, 25, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_ safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); #else - memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), 25); + memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h index 8fb410c2d63969636d2d2cf4f1c4c84b33988d6b..d365b7aedc4e1515167ccfb4c2cc7429292eb105 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h @@ -18,6 +18,9 @@ typedef struct __mavlink_safety_set_allowed_area_t #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 #define MAVLINK_MSG_ID_54_LEN 27 +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 +#define MAVLINK_MSG_ID_54_CRC 15 + #define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[27]; + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; _mav_put_float(buf, 0, p1x); _mav_put_float(buf, 4, p1y); _mav_put_float(buf, 8, p1z); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i _mav_put_uint8_t(buf, 25, target_component); _mav_put_uint8_t(buf, 26, frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); #else mavlink_safety_set_allowed_area_t packet; packet.p1x = p1x; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i packet.target_component = target_component; packet.frame = frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; - return mavlink_finalize_message(msg, system_id, component_id, 27, 15); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t sys uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[27]; + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; _mav_put_float(buf, 0, p1x); _mav_put_float(buf, 4, p1y); _mav_put_float(buf, 8, p1z); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t sys _mav_put_uint8_t(buf, 25, target_component); _mav_put_uint8_t(buf, 26, frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); #else mavlink_safety_set_allowed_area_t packet; packet.p1x = p1x; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t sys packet.target_component = target_component; packet.frame = frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 27, 15); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[27]; + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; _mav_put_float(buf, 0, p1x); _mav_put_float(buf, 4, p1y); _mav_put_float(buf, 8, p1z); @@ -184,7 +195,11 @@ static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t ch _mav_put_uint8_t(buf, 25, target_component); _mav_put_uint8_t(buf, 26, frame); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, 27, 15); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif #else mavlink_safety_set_allowed_area_t packet; packet.p1x = p1x; @@ -197,7 +212,11 @@ static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t ch packet.target_component = target_component; packet.frame = frame; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, 27, 15); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_mess safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); #else - memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), 27); + memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h index 8ff098f39f6714c1b60e5c21ca67f547b586b0f2..2751ddfe7ae88f2c038b96137247476dbc6f9042 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h @@ -19,6 +19,9 @@ typedef struct __mavlink_scaled_imu_t #define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 #define MAVLINK_MSG_ID_26_LEN 22 +#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 +#define MAVLINK_MSG_ID_26_CRC 170 + #define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, xacc); _mav_put_int16_t(buf, 6, yacc); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co _mav_put_int16_t(buf, 18, ymag); _mav_put_int16_t(buf, 20, zmag); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); #else mavlink_scaled_imu_t packet; packet.time_boot_ms = time_boot_ms; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; - return mavlink_finalize_message(msg, system_id, component_id, 22, 170); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif } /** @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8 uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, xacc); _mav_put_int16_t(buf, 6, yacc); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8 _mav_put_int16_t(buf, 18, ymag); _mav_put_int16_t(buf, 20, zmag); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); #else mavlink_scaled_imu_t packet; packet.time_boot_ms = time_boot_ms; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8 packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 170); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif } /** @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, xacc); _mav_put_int16_t(buf, 6, yacc); @@ -194,7 +205,11 @@ static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t _mav_put_int16_t(buf, 18, ymag); _mav_put_int16_t(buf, 20, zmag); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, 22, 170); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif #else mavlink_scaled_imu_t packet; packet.time_boot_ms = time_boot_ms; @@ -208,7 +223,11 @@ static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t packet.ymag = ymag; packet.zmag = zmag; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, 22, 170); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif #endif } @@ -337,6 +356,6 @@ static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, m scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); #else - memcpy(scaled_imu, _MAV_PAYLOAD(msg), 22); + memcpy(scaled_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h index d9ddcd47f9b6fa592446d27774fa6d84dad49ec0..f54e2819586a539622e3fc181edc25a80fd12a16 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h @@ -13,6 +13,9 @@ typedef struct __mavlink_scaled_pressure_t #define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 #define MAVLINK_MSG_ID_29_LEN 14 +#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 +#define MAVLINK_MSG_ID_29_CRC 115 + #define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8 uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, press_abs); _mav_put_float(buf, 8, press_diff); _mav_put_int16_t(buf, 12, temperature); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); #else mavlink_scaled_pressure_t packet; packet.time_boot_ms = time_boot_ms; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8 packet.press_diff = press_diff; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; - return mavlink_finalize_message(msg, system_id, component_id, 14, 115); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, press_abs); _mav_put_float(buf, 8, press_diff); _mav_put_int16_t(buf, 12, temperature); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); #else mavlink_scaled_pressure_t packet; packet.time_boot_ms = time_boot_ms; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, packet.press_diff = press_diff; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 115); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uin static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_float(buf, 4, press_abs); _mav_put_float(buf, 8, press_diff); _mav_put_int16_t(buf, 12, temperature); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, 14, 115); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif #else mavlink_scaled_pressure_t packet; packet.time_boot_ms = time_boot_ms; @@ -142,7 +157,11 @@ static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint packet.press_diff = press_diff; packet.temperature = temperature; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, 14, 115); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* m scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); #else - memcpy(scaled_pressure, _MAV_PAYLOAD(msg), 14); + memcpy(scaled_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h index 45c94d8b9cc00fa9eec9b18ee5f87434e0c3f2c4..10bdcbc8c20abc3cebdd0ed4be4a2e4636b4abea 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h @@ -19,6 +19,9 @@ typedef struct __mavlink_servo_output_raw_t #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 #define MAVLINK_MSG_ID_36_LEN 21 +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 +#define MAVLINK_MSG_ID_36_CRC 222 + #define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[21]; + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; _mav_put_uint32_t(buf, 0, time_usec); _mav_put_uint16_t(buf, 4, servo1_raw); _mav_put_uint16_t(buf, 6, servo2_raw); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint _mav_put_uint16_t(buf, 18, servo8_raw); _mav_put_uint8_t(buf, 20, port); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); #else mavlink_servo_output_raw_t packet; packet.time_usec = time_usec; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint packet.servo8_raw = servo8_raw; packet.port = port; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; - return mavlink_finalize_message(msg, system_id, component_id, 21, 222); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif } /** @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[21]; + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; _mav_put_uint32_t(buf, 0, time_usec); _mav_put_uint16_t(buf, 4, servo1_raw); _mav_put_uint16_t(buf, 6, servo2_raw); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, _mav_put_uint16_t(buf, 18, servo8_raw); _mav_put_uint8_t(buf, 20, port); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); #else mavlink_servo_output_raw_t packet; packet.time_usec = time_usec; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, packet.servo8_raw = servo8_raw; packet.port = port; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 222); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif } /** @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, ui static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[21]; + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; _mav_put_uint32_t(buf, 0, time_usec); _mav_put_uint16_t(buf, 4, servo1_raw); _mav_put_uint16_t(buf, 6, servo2_raw); @@ -194,7 +205,11 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin _mav_put_uint16_t(buf, 18, servo8_raw); _mav_put_uint8_t(buf, 20, port); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 21, 222); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif #else mavlink_servo_output_raw_t packet; packet.time_usec = time_usec; @@ -208,7 +223,11 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin packet.servo8_raw = servo8_raw; packet.port = port; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 21, 222); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif #endif } @@ -337,6 +356,6 @@ static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); #else - memcpy(servo_output_raw, _MAV_PAYLOAD(msg), 21); + memcpy(servo_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h index 5b706fb506747617c639ef2a8bef12eeb6bde629..0364b42415b7b2fb5c3781a13dec099e643b3e9a 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h @@ -4,9 +4,9 @@ typedef struct __mavlink_set_global_position_setpoint_int_t { - int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7 - int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7 - int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up) + int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 + int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7 + int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) int16_t yaw; ///< Desired yaw angle in degrees * 100 uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT } mavlink_set_global_position_setpoint_int_t; @@ -14,6 +14,9 @@ typedef struct __mavlink_set_global_position_setpoint_int_t #define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15 #define MAVLINK_MSG_ID_53_LEN 15 +#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC 33 +#define MAVLINK_MSG_ID_53_CRC 33 + #define MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT { \ @@ -35,9 +38,9 @@ typedef struct __mavlink_set_global_position_setpoint_int_t * @param msg The MAVLink message to compress the data into * * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude WGS84 Latitude position in degrees * 1E7 - * @param longitude WGS84 Longitude position in degrees * 1E7 - * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @param yaw Desired yaw angle in degrees * 100 * @return length of the message in bytes (excluding serial stream start sign) */ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_int16_t(buf, 12, yaw); _mav_put_uint8_t(buf, 14, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); #else mavlink_set_global_position_setpoint_int_t packet; packet.latitude = latitude; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; - return mavlink_finalize_message(msg, system_id, component_id, 15, 33); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif } /** @@ -75,9 +82,9 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude WGS84 Latitude position in degrees * 1E7 - * @param longitude WGS84 Longitude position in degrees * 1E7 - * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @param yaw Desired yaw angle in degrees * 100 * @return length of the message in bytes (excluding serial stream start sign) */ @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(ui uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_int16_t(buf, 12, yaw); _mav_put_uint8_t(buf, 14, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); #else mavlink_set_global_position_setpoint_int_t packet; packet.latitude = latitude; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(ui packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 33); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif } /** @@ -127,9 +138,9 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8 * @param chan MAVLink channel to send the message * * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude WGS84 Latitude position in degrees * 1E7 - * @param longitude WGS84 Longitude position in degrees * 1E7 - * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @param yaw Desired yaw angle in degrees * 100 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8 static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[15]; + char buf[MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_int16_t(buf, 12, yaw); _mav_put_uint8_t(buf, 14, coordinate_frame); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 33); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif #else mavlink_set_global_position_setpoint_int_t packet; packet.latitude = latitude; @@ -153,7 +168,11 @@ static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_cha packet.yaw = yaw; packet.coordinate_frame = coordinate_frame; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 33); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); +#endif #endif } @@ -175,7 +194,7 @@ static inline uint8_t mavlink_msg_set_global_position_setpoint_int_get_coordinat /** * @brief Get field latitude from set_global_position_setpoint_int message * - * @return WGS84 Latitude position in degrees * 1E7 + * @return Latitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) { @@ -185,7 +204,7 @@ static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude( /** * @brief Get field longitude from set_global_position_setpoint_int message * - * @return WGS84 Longitude position in degrees * 1E7 + * @return Longitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) { @@ -195,7 +214,7 @@ static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude /** * @brief Get field altitude from set_global_position_setpoint_int message * - * @return WGS84 Altitude in meters * 1000 (positive for up) + * @return Altitude (WGS84), in meters * 1000 (positive for up) */ static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) { @@ -227,6 +246,6 @@ static inline void mavlink_msg_set_global_position_setpoint_int_decode(const mav set_global_position_setpoint_int->yaw = mavlink_msg_set_global_position_setpoint_int_get_yaw(msg); set_global_position_setpoint_int->coordinate_frame = mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(msg); #else - memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), 15); + memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h index af404b1108e720c47f6f7ee85c96fd477f5c6751..e3cd4f44191de8d1cde80f98d754b3448a633d30 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h @@ -4,15 +4,18 @@ typedef struct __mavlink_set_gps_global_origin_t { - int32_t latitude; ///< global position * 1E7 - int32_t longitude; ///< global position * 1E7 - int32_t altitude; ///< global position * 1000 + int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 + int32_t longitude; ///< Longitude (WGS84, in degrees * 1E7 + int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) uint8_t target_system; ///< System ID } mavlink_set_gps_global_origin_t; #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 #define MAVLINK_MSG_ID_48_LEN 13 +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 +#define MAVLINK_MSG_ID_48_CRC 41 + #define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ @@ -33,22 +36,22 @@ typedef struct __mavlink_set_gps_global_origin_t * @param msg The MAVLink message to compress the data into * * @param target_system System ID - * @param latitude global position * 1E7 - * @param longitude global position * 1E7 - * @param altitude global position * 1000 + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[13]; + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_uint8_t(buf, 12, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); #else mavlink_set_gps_global_origin_t packet; packet.latitude = latitude; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, packet.altitude = altitude; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message(msg, system_id, component_id, 13, 41); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif } /** @@ -70,9 +77,9 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, * @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 latitude global position * 1E7 - * @param longitude global position * 1E7 - * @param altitude global position * 1000 + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t syste uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[13]; + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_uint8_t(buf, 12, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); #else mavlink_set_gps_global_origin_t packet; packet.latitude = latitude; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t syste packet.altitude = altitude; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 41); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif } /** @@ -119,22 +130,26 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_i * @param chan MAVLink channel to send the message * * @param target_system System ID - * @param latitude global position * 1E7 - * @param longitude global position * 1E7 - * @param altitude global position * 1000 + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[13]; + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; _mav_put_int32_t(buf, 0, latitude); _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); _mav_put_uint8_t(buf, 12, target_system); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, 13, 41); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif #else mavlink_set_gps_global_origin_t packet; packet.latitude = latitude; @@ -142,7 +157,11 @@ static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan packet.altitude = altitude; packet.target_system = target_system; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, 13, 41); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif #endif } @@ -164,7 +183,7 @@ static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const /** * @brief Get field latitude from set_gps_global_origin message * - * @return global position * 1E7 + * @return Latitude (WGS84), in degrees * 1E7 */ static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) { @@ -174,7 +193,7 @@ static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavli /** * @brief Get field longitude from set_gps_global_origin message * - * @return global position * 1E7 + * @return Longitude (WGS84, in degrees * 1E7 */ static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) { @@ -184,7 +203,7 @@ static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavl /** * @brief Get field altitude from set_gps_global_origin message * - * @return global position * 1000 + * @return Altitude (WGS84), in meters * 1000 (positive for up) */ static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) { @@ -205,6 +224,6 @@ static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_messag set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); #else - memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), 13); + memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h index 233e07d65cc9aa8c79f90830e81c4377c69934c0..b92c0560e93731db9f2067f94486b02ca4b88be2 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h @@ -16,6 +16,9 @@ typedef struct __mavlink_set_local_position_setpoint_t #define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19 #define MAVLINK_MSG_ID_50_LEN 19 +#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC 214 +#define MAVLINK_MSG_ID_50_CRC 214 + #define MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t syst uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[19]; + char buf[MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t syst _mav_put_uint8_t(buf, 17, target_component); _mav_put_uint8_t(buf, 18, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); #else mavlink_set_local_position_setpoint_t packet; packet.x = x; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t syst packet.target_component = target_component; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 19, 214); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,float x,float y,float z,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[19]; + char buf[MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t _mav_put_uint8_t(buf, 17, target_component); _mav_put_uint8_t(buf, 18, coordinate_frame); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); #else mavlink_set_local_position_setpoint_t packet; packet.x = x; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t packet.target_component = target_component; packet.coordinate_frame = coordinate_frame; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 19, 214); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_encode(uint8_t sy static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[19]; + char buf[MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -164,7 +175,11 @@ static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_ _mav_put_uint8_t(buf, 17, target_component); _mav_put_uint8_t(buf, 18, coordinate_frame); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, 19, 214); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); +#endif #else mavlink_set_local_position_setpoint_t packet; packet.x = x; @@ -175,7 +190,11 @@ static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_ packet.target_component = target_component; packet.coordinate_frame = coordinate_frame; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, 19, 214); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_set_local_position_setpoint_decode(const mavlink_ set_local_position_setpoint->target_component = mavlink_msg_set_local_position_setpoint_get_target_component(msg); set_local_position_setpoint->coordinate_frame = mavlink_msg_set_local_position_setpoint_get_coordinate_frame(msg); #else - memcpy(set_local_position_setpoint, _MAV_PAYLOAD(msg), 19); + memcpy(set_local_position_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h index fec21ab13791a0a20706423fb387bf1469b772fb..08ec7330983ec14f3857ad45e6a71ff1a4ca8b88 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h @@ -12,6 +12,9 @@ typedef struct __mavlink_set_mode_t #define MAVLINK_MSG_ID_SET_MODE_LEN 6 #define MAVLINK_MSG_ID_11_LEN 6 +#define MAVLINK_MSG_ID_SET_MODE_CRC 89 +#define MAVLINK_MSG_ID_11_CRC 89 + #define MAVLINK_MESSAGE_INFO_SET_MODE { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t comp uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; _mav_put_uint32_t(buf, 0, custom_mode); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, base_mode); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); #else mavlink_set_mode_t packet; packet.custom_mode = custom_mode; packet.target_system = target_system; packet.base_mode = base_mode; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_MODE; - return mavlink_finalize_message(msg, system_id, component_id, 6, 89); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; _mav_put_uint32_t(buf, 0, custom_mode); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, base_mode); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); #else mavlink_set_mode_t packet; packet.custom_mode = custom_mode; packet.target_system = target_system; packet.base_mode = base_mode; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_MODE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 89); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; _mav_put_uint32_t(buf, 0, custom_mode); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, base_mode); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, 6, 89); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif #else mavlink_set_mode_t packet; packet.custom_mode = custom_mode; packet.target_system = target_system; packet.base_mode = base_mode; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, 6, 89); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mav set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); #else - memcpy(set_mode, _MAV_PAYLOAD(msg), 6); + memcpy(set_mode, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MODE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h index 40ff8998ec46367418e6cf28a61f21b740d7a2d4..b79114e1a51da6781d98c0c06ef5b680334047cd 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h @@ -14,6 +14,9 @@ typedef struct __mavlink_set_quad_motors_setpoint_t #define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9 #define MAVLINK_MSG_ID_60_LEN 9 +#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC 30 +#define MAVLINK_MSG_ID_60_CRC 30 + #define MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack(uint8_t system_ uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN]; _mav_put_uint16_t(buf, 0, motor_front_nw); _mav_put_uint16_t(buf, 2, motor_right_ne); _mav_put_uint16_t(buf, 4, motor_back_se); _mav_put_uint16_t(buf, 6, motor_left_sw); _mav_put_uint8_t(buf, 8, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); #else mavlink_set_quad_motors_setpoint_t packet; packet.motor_front_nw = motor_front_nw; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack(uint8_t system_ packet.motor_left_sw = motor_left_sw; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 9, 30); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack_chan(uint8_t sy uint8_t target_system,uint16_t motor_front_nw,uint16_t motor_right_ne,uint16_t motor_back_se,uint16_t motor_left_sw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN]; _mav_put_uint16_t(buf, 0, motor_front_nw); _mav_put_uint16_t(buf, 2, motor_right_ne); _mav_put_uint16_t(buf, 4, motor_back_se); _mav_put_uint16_t(buf, 6, motor_left_sw); _mav_put_uint8_t(buf, 8, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); #else mavlink_set_quad_motors_setpoint_t packet; packet.motor_front_nw = motor_front_nw; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack_chan(uint8_t sy packet.motor_left_sw = motor_left_sw; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 30); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode(uint8_t syste static inline void mavlink_msg_set_quad_motors_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[9]; + char buf[MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN]; _mav_put_uint16_t(buf, 0, motor_front_nw); _mav_put_uint16_t(buf, 2, motor_right_ne); _mav_put_uint16_t(buf, 4, motor_back_se); _mav_put_uint16_t(buf, 6, motor_left_sw); _mav_put_uint8_t(buf, 8, target_system); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, 9, 30); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); +#endif #else mavlink_set_quad_motors_setpoint_t packet; packet.motor_front_nw = motor_front_nw; @@ -153,7 +168,11 @@ static inline void mavlink_msg_set_quad_motors_setpoint_send(mavlink_channel_t c packet.motor_left_sw = motor_left_sw; packet.target_system = target_system; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, 9, 30); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_set_quad_motors_setpoint_decode(const mavlink_mes set_quad_motors_setpoint->motor_left_sw = mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(msg); set_quad_motors_setpoint->target_system = mavlink_msg_set_quad_motors_setpoint_get_target_system(msg); #else - memcpy(set_quad_motors_setpoint, _MAV_PAYLOAD(msg), 9); + memcpy(set_quad_motors_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h index 75a1420a1d10d330f4d9947114ffe17e4f8fdacf..06223845f485d8f83a6d66b85a8d037364eea375 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h @@ -18,6 +18,9 @@ typedef struct __mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t #define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN 46 #define MAVLINK_MSG_ID_63_LEN 46 +#define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC 130 +#define MAVLINK_MSG_ID_63_CRC 130 + #define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 4 #define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 4 #define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 4 @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[46]; + char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_uint8_t(buf, 32, group); _mav_put_uint8_t(buf, 33, mode); _mav_put_int16_t_array(buf, 0, roll, 4); @@ -73,7 +76,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack _mav_put_uint8_t_array(buf, 34, led_red, 4); _mav_put_uint8_t_array(buf, 38, led_blue, 4); _mav_put_uint8_t_array(buf, 42, led_green, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 46); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); #else mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet; packet.group = group; @@ -85,11 +88,15 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4); mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4); mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 46); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST; - return mavlink_finalize_message(msg, system_id, component_id, 46, 130); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); +#endif } /** @@ -114,7 +121,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack uint8_t group,uint8_t mode,const uint8_t *led_red,const uint8_t *led_blue,const uint8_t *led_green,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[46]; + char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_uint8_t(buf, 32, group); _mav_put_uint8_t(buf, 33, mode); _mav_put_int16_t_array(buf, 0, roll, 4); @@ -124,7 +131,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack _mav_put_uint8_t_array(buf, 34, led_red, 4); _mav_put_uint8_t_array(buf, 38, led_blue, 4); _mav_put_uint8_t_array(buf, 42, led_green, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 46); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); #else mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet; packet.group = group; @@ -136,11 +143,15 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4); mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4); mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 46); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 46, 130); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); +#endif } /** @@ -175,7 +186,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_enco static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[46]; + char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_uint8_t(buf, 32, group); _mav_put_uint8_t(buf, 33, mode); _mav_put_int16_t_array(buf, 0, roll, 4); @@ -185,7 +196,11 @@ static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(mav _mav_put_uint8_t_array(buf, 34, led_red, 4); _mav_put_uint8_t_array(buf, 38, led_blue, 4); _mav_put_uint8_t_array(buf, 42, led_green, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, 46, 130); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); +#endif #else mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet; packet.group = group; @@ -197,7 +212,11 @@ static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(mav mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4); mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4); mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 46, 130); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(c mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_blue(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue); mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_green(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green); #else - memcpy(set_quad_swarm_led_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 46); + memcpy(set_quad_swarm_led_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h index 35c5db18c8371be1f142b81bbad67f5de5443a6e..6c62b35305da648aec6f1dc48cf271c251536da0 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h @@ -15,6 +15,9 @@ typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t #define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 34 #define MAVLINK_MSG_ID_61_LEN 34 +#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC 240 +#define MAVLINK_MSG_ID_61_CRC 240 + #define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 4 #define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 4 #define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 4 @@ -51,14 +54,14 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uin uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[34]; + char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_uint8_t(buf, 32, group); _mav_put_uint8_t(buf, 33, mode); _mav_put_int16_t_array(buf, 0, roll, 4); _mav_put_int16_t_array(buf, 8, pitch, 4); _mav_put_int16_t_array(buf, 16, yaw, 4); _mav_put_uint16_t_array(buf, 24, thrust, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); #else mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; packet.group = group; @@ -67,11 +70,15 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uin mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST; - return mavlink_finalize_message(msg, system_id, component_id, 34, 240); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); +#endif } /** @@ -93,14 +100,14 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_cha uint8_t group,uint8_t mode,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[34]; + char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_uint8_t(buf, 32, group); _mav_put_uint8_t(buf, 33, mode); _mav_put_int16_t_array(buf, 0, roll, 4); _mav_put_int16_t_array(buf, 8, pitch, 4); _mav_put_int16_t_array(buf, 16, yaw, 4); _mav_put_uint16_t_array(buf, 24, thrust, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); #else mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; packet.group = group; @@ -109,11 +116,15 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_cha mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 34); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 34, 240); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); +#endif } /** @@ -145,14 +156,18 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(u static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[34]; + char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_uint8_t(buf, 32, group); _mav_put_uint8_t(buf, 33, mode); _mav_put_int16_t_array(buf, 0, roll, 4); _mav_put_int16_t_array(buf, 8, pitch, 4); _mav_put_int16_t_array(buf, 16, yaw, 4); _mav_put_uint16_t_array(buf, 24, thrust, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, 34, 240); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); +#endif #else mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; packet.group = group; @@ -161,7 +176,11 @@ static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 34, 240); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); +#endif #endif } @@ -246,6 +265,6 @@ static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(const set_quad_swarm_roll_pitch_yaw_thrust->group = mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_group(msg); set_quad_swarm_roll_pitch_yaw_thrust->mode = mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_mode(msg); #else - memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 34); + memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h index b79a7e9f2fd3bb519d36acf0d70b65e74e9604b7..c379a75d9bb8bac484be0d53464de6f0ddde647e 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h @@ -15,6 +15,9 @@ typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t #define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18 #define MAVLINK_MSG_ID_57_LEN 18 +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC 24 +#define MAVLINK_MSG_ID_57_CRC 24 + #define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN]; _mav_put_float(buf, 0, roll_speed); _mav_put_float(buf, 4, pitch_speed); _mav_put_float(buf, 8, yaw_speed); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); #else mavlink_set_roll_pitch_yaw_speed_thrust_t packet; packet.roll_speed = roll_speed; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; - return mavlink_finalize_message(msg, system_id, component_id, 18, 24); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uin uint8_t target_system,uint8_t target_component,float roll_speed,float pitch_speed,float yaw_speed,float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN]; _mav_put_float(buf, 0, roll_speed); _mav_put_float(buf, 4, pitch_speed); _mav_put_float(buf, 8, yaw_speed); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uin _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); #else mavlink_set_roll_pitch_yaw_speed_thrust_t packet; packet.roll_speed = roll_speed; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uin packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 24); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_ static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN]; _mav_put_float(buf, 0, roll_speed); _mav_put_float(buf, 4, pitch_speed); _mav_put_float(buf, 8, yaw_speed); @@ -154,7 +165,11 @@ static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_chan _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, 18, 24); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); +#endif #else mavlink_set_roll_pitch_yaw_speed_thrust_t packet; packet.roll_speed = roll_speed; @@ -164,7 +179,11 @@ static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_chan packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, 18, 24); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavl set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg); set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg); #else - memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), 18); + memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h index 8cd573a26c561e658bcdb255873dbac00a3983ab..146891eafb1b8ca6a78a9d2ebe3df1c62d469612 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h @@ -15,6 +15,9 @@ typedef struct __mavlink_set_roll_pitch_yaw_thrust_t #define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18 #define MAVLINK_MSG_ID_56_LEN 18 +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC 100 +#define MAVLINK_MSG_ID_56_CRC 100 + #define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); #else mavlink_set_roll_pitch_yaw_thrust_t packet; packet.roll = roll; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; - return mavlink_finalize_message(msg, system_id, component_id, 18, 100); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t s uint8_t target_system,uint8_t target_component,float roll,float pitch,float yaw,float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t s _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); #else mavlink_set_roll_pitch_yaw_thrust_t packet; packet.roll = roll; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t s packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 100); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t syst static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -154,7 +165,11 @@ static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, 18, 100); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); +#endif #else mavlink_set_roll_pitch_yaw_thrust_t packet; packet.roll = roll; @@ -164,7 +179,11 @@ static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 18, 100); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_me set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg); set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg); #else - memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 18); + memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h index fec38a6a481d88a895475d64357b1539cb840f31..f352617a266d09c1a7110b13d7ac6a1c99a64b26 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h @@ -16,6 +16,9 @@ typedef struct __mavlink_setpoint_6dof_t #define MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25 #define MAVLINK_MSG_ID_149_LEN 25 +#define MAVLINK_MSG_ID_SETPOINT_6DOF_CRC 15 +#define MAVLINK_MSG_ID_149_CRC 15 + #define MAVLINK_MESSAGE_INFO_SETPOINT_6DOF { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN]; _mav_put_float(buf, 0, trans_x); _mav_put_float(buf, 4, trans_y); _mav_put_float(buf, 8, trans_z); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t _mav_put_float(buf, 20, rot_z); _mav_put_uint8_t(buf, 24, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); #else mavlink_setpoint_6dof_t packet; packet.trans_x = trans_x; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t packet.rot_z = rot_z; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF; - return mavlink_finalize_message(msg, system_id, component_id, 25, 15); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN]; _mav_put_float(buf, 0, trans_x); _mav_put_float(buf, 4, trans_y); _mav_put_float(buf, 8, trans_z); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui _mav_put_float(buf, 20, rot_z); _mav_put_uint8_t(buf, 24, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); #else mavlink_setpoint_6dof_t packet; packet.trans_x = trans_x; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui packet.rot_z = rot_z; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 15); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_encode(uint8_t system_id, uint8 static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[25]; + char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN]; _mav_put_float(buf, 0, trans_x); _mav_put_float(buf, 4, trans_y); _mav_put_float(buf, 8, trans_z); @@ -164,7 +175,11 @@ static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_ _mav_put_float(buf, 20, rot_z); _mav_put_uint8_t(buf, 24, target_system); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, 25, 15); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); +#endif #else mavlink_setpoint_6dof_t packet; packet.trans_x = trans_x; @@ -175,7 +190,11 @@ static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_ packet.rot_z = rot_z; packet.target_system = target_system; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, 25, 15); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_setpoint_6dof_decode(const mavlink_message_t* msg setpoint_6dof->rot_z = mavlink_msg_setpoint_6dof_get_rot_z(msg); setpoint_6dof->target_system = mavlink_msg_setpoint_6dof_get_target_system(msg); #else - memcpy(setpoint_6dof, _MAV_PAYLOAD(msg), 25); + memcpy(setpoint_6dof, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h index bc761be08db37b42b523c4dd63b8e20ff25fc0e8..d7622b6965d97d2a99f3e2136060554ddd3ca951 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h @@ -18,6 +18,9 @@ typedef struct __mavlink_setpoint_8dof_t #define MAVLINK_MSG_ID_SETPOINT_8DOF_LEN 33 #define MAVLINK_MSG_ID_148_LEN 33 +#define MAVLINK_MSG_ID_SETPOINT_8DOF_CRC 241 +#define MAVLINK_MSG_ID_148_CRC 241 + #define MAVLINK_MESSAGE_INFO_SETPOINT_8DOF { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack(uint8_t system_id, uint8_t uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_SETPOINT_8DOF_LEN]; _mav_put_float(buf, 0, val1); _mav_put_float(buf, 4, val2); _mav_put_float(buf, 8, val3); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack(uint8_t system_id, uint8_t _mav_put_float(buf, 28, val8); _mav_put_uint8_t(buf, 32, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); #else mavlink_setpoint_8dof_t packet; packet.val1 = val1; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack(uint8_t system_id, uint8_t packet.val8 = val8; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SETPOINT_8DOF; - return mavlink_finalize_message(msg, system_id, component_id, 33, 241); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack_chan(uint8_t system_id, ui uint8_t target_system,float val1,float val2,float val3,float val4,float val5,float val6,float val7,float val8) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_SETPOINT_8DOF_LEN]; _mav_put_float(buf, 0, val1); _mav_put_float(buf, 4, val2); _mav_put_float(buf, 8, val3); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack_chan(uint8_t system_id, ui _mav_put_float(buf, 28, val8); _mav_put_uint8_t(buf, 32, target_system); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); #else mavlink_setpoint_8dof_t packet; packet.val1 = val1; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack_chan(uint8_t system_id, ui packet.val8 = val8; packet.target_system = target_system; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SETPOINT_8DOF; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 241); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_encode(uint8_t system_id, uint8 static inline void mavlink_msg_setpoint_8dof_send(mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[33]; + char buf[MAVLINK_MSG_ID_SETPOINT_8DOF_LEN]; _mav_put_float(buf, 0, val1); _mav_put_float(buf, 4, val2); _mav_put_float(buf, 8, val3); @@ -184,7 +195,11 @@ static inline void mavlink_msg_setpoint_8dof_send(mavlink_channel_t chan, uint8_ _mav_put_float(buf, 28, val8); _mav_put_uint8_t(buf, 32, target_system); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, 33, 241); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); +#endif #else mavlink_setpoint_8dof_t packet; packet.val1 = val1; @@ -197,7 +212,11 @@ static inline void mavlink_msg_setpoint_8dof_send(mavlink_channel_t chan, uint8_ packet.val8 = val8; packet.target_system = target_system; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)&packet, 33, 241); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_setpoint_8dof_decode(const mavlink_message_t* msg setpoint_8dof->val8 = mavlink_msg_setpoint_8dof_get_val8(msg); setpoint_8dof->target_system = mavlink_msg_setpoint_8dof_get_target_system(msg); #else - memcpy(setpoint_8dof, _MAV_PAYLOAD(msg), 33); + memcpy(setpoint_8dof, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h new file mode 100644 index 0000000000000000000000000000000000000000..956f2357779f2efaf8f29197c494ca832da1f64e --- /dev/null +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h @@ -0,0 +1,383 @@ +// MESSAGE SIM_STATE PACKING + +#define MAVLINK_MSG_ID_SIM_STATE 108 + +typedef struct __mavlink_sim_state_t +{ + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float xacc; ///< X acceleration m/s/s + float yacc; ///< Y acceleration m/s/s + float zacc; ///< Z acceleration m/s/s + float xgyro; ///< Angular speed around X axis rad/s + float ygyro; ///< Angular speed around Y axis rad/s + float zgyro; ///< Angular speed around Z axis rad/s + float lat; ///< Latitude in degrees + float lng; ///< Longitude in degrees +} mavlink_sim_state_t; + +#define MAVLINK_MSG_ID_SIM_STATE_LEN 44 +#define MAVLINK_MSG_ID_108_LEN 44 + +#define MAVLINK_MSG_ID_SIM_STATE_CRC 212 +#define MAVLINK_MSG_ID_108_CRC 212 + + + +#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ + "SIM_STATE", \ + 11, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, yaw) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, zgyro) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, lat) }, \ + { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, lng) }, \ + } \ +} + + +/** + * @brief Pack a sim_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 roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lng Longitude in degrees + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + _mav_put_float(buf, 36, lat); + _mav_put_float(buf, 40, lng); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#else + mavlink_sim_state_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lng = lng; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} + +/** + * @brief Pack a sim_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lng Longitude in degrees + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lng) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + _mav_put_float(buf, 36, lat); + _mav_put_float(buf, 40, lng); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#else + mavlink_sim_state_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lng = lng; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} + +/** + * @brief Encode a sim_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 sim_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) +{ + return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lng); +} + +/** + * @brief Send a sim_state message + * @param chan MAVLink channel to send the message + * + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lng Longitude in degrees + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + _mav_put_float(buf, 36, lat); + _mav_put_float(buf, 40, lng); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#else + mavlink_sim_state_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lng = lng; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#endif +} + +#endif + +// MESSAGE SIM_STATE UNPACKING + + +/** + * @brief Get field roll from sim_state message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from sim_state message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from sim_state message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field xacc from sim_state message + * + * @return X acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yacc from sim_state message + * + * @return Y acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field zacc from sim_state message + * + * @return Z acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field xgyro from sim_state message + * + * @return Angular speed around X axis rad/s + */ +static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field ygyro from sim_state message + * + * @return Angular speed around Y axis rad/s + */ +static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field zgyro from sim_state message + * + * @return Angular speed around Z axis rad/s + */ +static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field lat from sim_state message + * + * @return Latitude in degrees + */ +static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field lng from sim_state message + * + * @return Longitude in degrees + */ +static inline float mavlink_msg_sim_state_get_lng(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Decode a sim_state message into a struct + * + * @param msg The message to decode + * @param sim_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + sim_state->roll = mavlink_msg_sim_state_get_roll(msg); + sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg); + sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg); + sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg); + sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg); + sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg); + sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg); + sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg); + sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg); + sim_state->lat = mavlink_msg_sim_state_get_lat(msg); + sim_state->lng = mavlink_msg_sim_state_get_lng(msg); +#else + memcpy(sim_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h index 0f4f1f5e22bff94c46af0c96dd5210ceaf67b2ec..8a002fc11327eb91481f3598614275199790e324 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h @@ -18,6 +18,9 @@ typedef struct __mavlink_state_correction_t #define MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36 #define MAVLINK_MSG_ID_64_LEN 36 +#define MAVLINK_MSG_ID_STATE_CORRECTION_CRC 130 +#define MAVLINK_MSG_ID_64_CRC 130 + #define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[MAVLINK_MSG_ID_STATE_CORRECTION_LEN]; _mav_put_float(buf, 0, xErr); _mav_put_float(buf, 4, yErr); _mav_put_float(buf, 8, zErr); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint _mav_put_float(buf, 28, vyErr); _mav_put_float(buf, 32, vzErr); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); #else mavlink_state_correction_t packet; packet.xErr = xErr; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint packet.vyErr = vyErr; packet.vzErr = vzErr; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; - return mavlink_finalize_message(msg, system_id, component_id, 36, 130); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, float xErr,float yErr,float zErr,float rollErr,float pitchErr,float yawErr,float vxErr,float vyErr,float vzErr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[MAVLINK_MSG_ID_STATE_CORRECTION_LEN]; _mav_put_float(buf, 0, xErr); _mav_put_float(buf, 4, yErr); _mav_put_float(buf, 8, zErr); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, _mav_put_float(buf, 28, vyErr); _mav_put_float(buf, 32, vzErr); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); #else mavlink_state_correction_t packet; packet.xErr = xErr; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, packet.vyErr = vyErr; packet.vzErr = vzErr; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 130); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, ui static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[36]; + char buf[MAVLINK_MSG_ID_STATE_CORRECTION_LEN]; _mav_put_float(buf, 0, xErr); _mav_put_float(buf, 4, yErr); _mav_put_float(buf, 8, zErr); @@ -184,7 +195,11 @@ static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, flo _mav_put_float(buf, 28, vyErr); _mav_put_float(buf, 32, vzErr); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, 36, 130); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); +#endif #else mavlink_state_correction_t packet; packet.xErr = xErr; @@ -197,7 +212,11 @@ static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, flo packet.vyErr = vyErr; packet.vzErr = vzErr; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, 36, 130); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg); state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg); #else - memcpy(state_correction, _MAV_PAYLOAD(msg), 36); + memcpy(state_correction, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATE_CORRECTION_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h index 7c65d448f436d7331bb52d0f84293d1695982c55..103486863cedcf18a0057378c7a8670272b1f273 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h @@ -11,6 +11,9 @@ typedef struct __mavlink_statustext_t #define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 #define MAVLINK_MSG_ID_253_LEN 51 +#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 +#define MAVLINK_MSG_ID_253_CRC 83 + #define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 #define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ @@ -36,19 +39,23 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co uint8_t severity, const char *text) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[51]; + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; _mav_put_uint8_t(buf, 0, severity); _mav_put_char_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); #else mavlink_statustext_t packet; packet.severity = severity; mav_array_memcpy(packet.text, text, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message(msg, system_id, component_id, 51, 83); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif } /** @@ -66,19 +73,23 @@ static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8 uint8_t severity,const char *text) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[51]; + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; _mav_put_uint8_t(buf, 0, severity); _mav_put_char_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); #else mavlink_statustext_t packet; packet.severity = severity; mav_array_memcpy(packet.text, text, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 51, 83); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif } /** @@ -106,15 +117,23 @@ static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[51]; + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; _mav_put_uint8_t(buf, 0, severity); _mav_put_char_array(buf, 1, text, 50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, 51, 83); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif #else mavlink_statustext_t packet; packet.severity = severity; mav_array_memcpy(packet.text, text, sizeof(char)*50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, 51, 83); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif #endif } @@ -155,6 +174,6 @@ static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, m statustext->severity = mavlink_msg_statustext_get_severity(msg); mavlink_msg_statustext_get_text(msg, statustext->text); #else - memcpy(statustext, _MAV_PAYLOAD(msg), 51); + memcpy(statustext, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATUSTEXT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h index ef09a652f8bce55bf3866775a6d0d9483a9036da..916bc4f07b2f9e717b393bb10e7efb61beb8bb55 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h @@ -22,6 +22,9 @@ typedef struct __mavlink_sys_status_t #define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 #define MAVLINK_MSG_ID_1_LEN 31 +#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 +#define MAVLINK_MSG_ID_1_CRC 124 + #define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ @@ -69,7 +72,7 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[31]; + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); @@ -84,7 +87,7 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co _mav_put_uint16_t(buf, 28, errors_count4); _mav_put_int8_t(buf, 30, battery_remaining); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); #else mavlink_sys_status_t packet; packet.onboard_control_sensors_present = onboard_control_sensors_present; @@ -101,11 +104,15 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co packet.errors_count4 = errors_count4; packet.battery_remaining = battery_remaining; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 31, 124); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif } /** @@ -134,7 +141,7 @@ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8 uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[31]; + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); @@ -149,7 +156,7 @@ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8 _mav_put_uint16_t(buf, 28, errors_count4); _mav_put_int8_t(buf, 30, battery_remaining); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); #else mavlink_sys_status_t packet; packet.onboard_control_sensors_present = onboard_control_sensors_present; @@ -166,11 +173,15 @@ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8 packet.errors_count4 = errors_count4; packet.battery_remaining = battery_remaining; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 31, 124); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif } /** @@ -209,7 +220,7 @@ static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[31]; + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); @@ -224,7 +235,11 @@ static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t _mav_put_uint16_t(buf, 28, errors_count4); _mav_put_int8_t(buf, 30, battery_remaining); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 31, 124); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif #else mavlink_sys_status_t packet; packet.onboard_control_sensors_present = onboard_control_sensors_present; @@ -241,7 +256,11 @@ static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t packet.errors_count4 = errors_count4; packet.battery_remaining = battery_remaining; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 31, 124); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif #endif } @@ -403,6 +422,6 @@ static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, m sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); #else - memcpy(sys_status, _MAV_PAYLOAD(msg), 31); + memcpy(sys_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYS_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h index c24808d1a2c180e1eb12190e959bfbc344d187b9..b235fe20560affeeafa39ce1317280b9fba7ae26 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h @@ -11,6 +11,9 @@ typedef struct __mavlink_system_time_t #define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 #define MAVLINK_MSG_ID_2_LEN 12 +#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 +#define MAVLINK_MSG_ID_2_CRC 137 + #define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t c uint64_t time_unix_usec, uint32_t time_boot_ms) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; _mav_put_uint64_t(buf, 0, time_unix_usec); _mav_put_uint32_t(buf, 8, time_boot_ms); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); #else mavlink_system_time_t packet; packet.time_unix_usec = time_unix_usec; packet.time_boot_ms = time_boot_ms; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; - return mavlink_finalize_message(msg, system_id, component_id, 12, 137); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint uint64_t time_unix_usec,uint32_t time_boot_ms) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; _mav_put_uint64_t(buf, 0, time_unix_usec); _mav_put_uint32_t(buf, 8, time_boot_ms); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); #else mavlink_system_time_t packet; packet.time_unix_usec = time_unix_usec; packet.time_boot_ms = time_boot_ms; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 137); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; _mav_put_uint64_t(buf, 0, time_unix_usec); _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, 12, 137); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif #else mavlink_system_time_t packet; packet.time_unix_usec = time_unix_usec; packet.time_boot_ms = time_boot_ms; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, 12, 137); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); #else - memcpy(system_time, _MAV_PAYLOAD(msg), 12); + memcpy(system_time, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYSTEM_TIME_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h index d7c1afe410727f890e7d392c565084013a9d536c..9d459921fe55d65ef4532f627ee522ba7413439e 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h @@ -15,6 +15,9 @@ typedef struct __mavlink_vfr_hud_t #define MAVLINK_MSG_ID_VFR_HUD_LEN 20 #define MAVLINK_MSG_ID_74_LEN 20 +#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 +#define MAVLINK_MSG_ID_74_CRC 20 + #define MAVLINK_MESSAGE_INFO_VFR_HUD { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; _mav_put_float(buf, 0, airspeed); _mav_put_float(buf, 4, groundspeed); _mav_put_float(buf, 8, alt); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo _mav_put_int16_t(buf, 16, heading); _mav_put_uint16_t(buf, 18, throttle); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); #else mavlink_vfr_hud_t packet; packet.airspeed = airspeed; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo packet.heading = heading; packet.throttle = throttle; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VFR_HUD; - return mavlink_finalize_message(msg, system_id, component_id, 20, 20); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; _mav_put_float(buf, 0, airspeed); _mav_put_float(buf, 4, groundspeed); _mav_put_float(buf, 8, alt); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t _mav_put_int16_t(buf, 16, heading); _mav_put_uint16_t(buf, 18, throttle); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); #else mavlink_vfr_hud_t packet; packet.airspeed = airspeed; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t packet.heading = heading; packet.throttle = throttle; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VFR_HUD; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 20); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; _mav_put_float(buf, 0, airspeed); _mav_put_float(buf, 4, groundspeed); _mav_put_float(buf, 8, alt); @@ -154,7 +165,11 @@ static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspe _mav_put_int16_t(buf, 16, heading); _mav_put_uint16_t(buf, 18, throttle); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, 20, 20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif #else mavlink_vfr_hud_t packet; packet.airspeed = airspeed; @@ -164,7 +179,11 @@ static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspe packet.heading = heading; packet.throttle = throttle; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, 20, 20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavl vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); #else - memcpy(vfr_hud, _MAV_PAYLOAD(msg), 20); + memcpy(vfr_hud, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VFR_HUD_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h index 93ad097f91a6e359429a1be9c3cbcdaa16bb131d..75e4b5b7abdafb099d7415ab502d0e6fb564ff84 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h @@ -16,6 +16,9 @@ typedef struct __mavlink_vicon_position_estimate_t #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 #define MAVLINK_MSG_ID_104_LEN 32 +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 +#define MAVLINK_MSG_ID_104_CRC 56 + #define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); #else mavlink_vicon_position_estimate_t packet; packet.usec = usec; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 32, 56); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t sys uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t sys _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); #else mavlink_vicon_position_estimate_t packet; packet.usec = usec; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t sys packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 56); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -164,7 +175,11 @@ static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t ch _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32, 56); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif #else mavlink_vicon_position_estimate_t packet; packet.usec = usec; @@ -175,7 +190,11 @@ static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t ch packet.pitch = pitch; packet.yaw = yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32, 56); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_mess vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); #else - memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), 32); + memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h index ca567c1191954266a1f65dacf4aa1353e57afda5..47ccb11ec0dc1942142f3e5dfe02f9cbf181a3ab 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h @@ -16,6 +16,9 @@ typedef struct __mavlink_vision_position_estimate_t #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 #define MAVLINK_MSG_ID_102_LEN 32 +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 +#define MAVLINK_MSG_ID_102_CRC 158 + #define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_ uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_ _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); #else mavlink_vision_position_estimate_t packet; packet.usec = usec; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_ packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 32, 158); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t sy uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t sy _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); #else mavlink_vision_position_estimate_t packet; packet.usec = usec; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t sy packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 158); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t syste static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); @@ -164,7 +175,11 @@ static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t c _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32, 158); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif #else mavlink_vision_position_estimate_t packet; packet.usec = usec; @@ -175,7 +190,11 @@ static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t c packet.pitch = pitch; packet.yaw = yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 158); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_mes vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); #else - memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), 32); + memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h index 10ec1026c76e9324b2c6d265d7bc8def88e5210d..c38eee62c00c88813933f6aa86d0b36f4b37c3f5 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h +++ b/libs/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h @@ -13,6 +13,9 @@ typedef struct __mavlink_vision_speed_estimate_t #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 #define MAVLINK_MSG_ID_103_LEN 20 +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 +#define MAVLINK_MSG_ID_103_CRC 208 + #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint64_t usec, float x, float y, float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); #else mavlink_vision_speed_estimate_t packet; packet.usec = usec; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, packet.y = y; packet.z = z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 20, 208); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t syste uint64_t usec,float x,float y,float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); #else mavlink_vision_speed_estimate_t packet; packet.usec = usec; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t syste packet.y = y; packet.z = z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 208); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_i static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; _mav_put_uint64_t(buf, 0, usec); _mav_put_float(buf, 8, x); _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20, 208); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif #else mavlink_vision_speed_estimate_t packet; packet.usec = usec; @@ -142,7 +157,11 @@ static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan packet.y = y; packet.z = z; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20, 208); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_messag vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); #else - memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), 20); + memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/common/testsuite.h b/libs/mavlink/include/mavlink/v1.0/common/testsuite.h index 0da36c7d8f178c143c671f8795272d0aebb0a6d9..ead898afd634d6ae705272bc05299a2cdb6ab09f 100644 --- a/libs/mavlink/include/mavlink/v1.0/common/testsuite.h +++ b/libs/mavlink/include/mavlink/v1.0/common/testsuite.h @@ -3939,6 +3939,207 @@ static void mavlink_test_omnidirectional_flow(uint8_t system_id, uint8_t compone MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_hil_sensor(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_hil_sensor_t packet_in = { + 93372036854775807ULL, + 73.0, + 101.0, + 129.0, + 963498504, + 963498712, + 213.0, + 241.0, + 269.0, + 297.0, + 325.0, + 353.0, + 381.0, + 409.0, + 437.0, + 465.0, + 493.0, + 521.0, + 549.0, + 577.0, + 963501832, + }; + mavlink_hil_sensor_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.time_usec = packet_in.time_usec; + packet1.roll = packet_in.roll; + packet1.pitch = packet_in.pitch; + packet1.yaw = packet_in.yaw; + packet1.lat = packet_in.lat; + packet1.lon = packet_in.lon; + packet1.xacc = packet_in.xacc; + packet1.yacc = packet_in.yacc; + packet1.zacc = packet_in.zacc; + packet1.xgyro = packet_in.xgyro; + packet1.ygyro = packet_in.ygyro; + packet1.zgyro = packet_in.zgyro; + packet1.xmag = packet_in.xmag; + packet1.ymag = packet_in.ymag; + packet1.zmag = packet_in.zmag; + packet1.abs_pressure = packet_in.abs_pressure; + packet1.diff_pressure = packet_in.diff_pressure; + packet1.pressure_alt = packet_in.pressure_alt; + packet1.gps_alt = packet_in.gps_alt; + packet1.temperature = packet_in.temperature; + packet1.fields_updated = packet_in.fields_updated; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_hil_sensor_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_hil_sensor_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_hil_sensor_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.lat , packet1.lon , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.gps_alt , packet1.temperature , packet1.fields_updated ); + mavlink_msg_hil_sensor_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_hil_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.lat , packet1.lon , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.gps_alt , packet1.temperature , packet1.fields_updated ); + mavlink_msg_hil_sensor_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imsgid = MAVLINK_MSG_ID_AIRSPEEDS; - return mavlink_finalize_message(msg, system_id, component_id, 16, 154); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEEDS_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_airspeeds_pack_chan(uint8_t system_id, uint8_ uint32_t time_boot_ms,int16_t airspeed_imu,int16_t airspeed_pitot,int16_t airspeed_hot_wire,int16_t airspeed_ultrasonic,int16_t aoa,int16_t aoy) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_AIRSPEEDS_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, airspeed_imu); _mav_put_int16_t(buf, 6, airspeed_pitot); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_airspeeds_pack_chan(uint8_t system_id, uint8_ _mav_put_int16_t(buf, 12, aoa); _mav_put_int16_t(buf, 14, aoy); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN); #else mavlink_airspeeds_t packet; packet.time_boot_ms = time_boot_ms; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_airspeeds_pack_chan(uint8_t system_id, uint8_ packet.aoa = aoa; packet.aoy = aoy; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_AIRSPEEDS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 154); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEEDS_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_airspeeds_encode(uint8_t system_id, uint8_t c static inline void mavlink_msg_airspeeds_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_AIRSPEEDS_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int16_t(buf, 4, airspeed_imu); _mav_put_int16_t(buf, 6, airspeed_pitot); @@ -164,7 +175,11 @@ static inline void mavlink_msg_airspeeds_send(mavlink_channel_t chan, uint32_t t _mav_put_int16_t(buf, 12, aoa); _mav_put_int16_t(buf, 14, aoy); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, 16, 154); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN); +#endif #else mavlink_airspeeds_t packet; packet.time_boot_ms = time_boot_ms; @@ -175,7 +190,11 @@ static inline void mavlink_msg_airspeeds_send(mavlink_channel_t chan, uint32_t t packet.aoa = aoa; packet.aoy = aoy; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)&packet, 16, 154); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_airspeeds_decode(const mavlink_message_t* msg, ma airspeeds->aoa = mavlink_msg_airspeeds_get_aoa(msg); airspeeds->aoy = mavlink_msg_airspeeds_get_aoy(msg); #else - memcpy(airspeeds, _MAV_PAYLOAD(msg), 16); + memcpy(airspeeds, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AIRSPEEDS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h index e77dcde49514db3b35734d85380e80438323de0d..c1ce66875ce9ae05710fcf8c00f4581d47564b3a 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h @@ -16,6 +16,9 @@ typedef struct __mavlink_altitudes_t #define MAVLINK_MSG_ID_ALTITUDES_LEN 28 #define MAVLINK_MSG_ID_181_LEN 28 +#define MAVLINK_MSG_ID_ALTITUDES_CRC 55 +#define MAVLINK_MSG_ID_181_CRC 55 + #define MAVLINK_MESSAGE_INFO_ALTITUDES { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t com uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_ALTITUDES_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, alt_gps); _mav_put_int32_t(buf, 8, alt_imu); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t com _mav_put_int32_t(buf, 20, alt_range_finder); _mav_put_int32_t(buf, 24, alt_extra); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDES_LEN); #else mavlink_altitudes_t packet; packet.time_boot_ms = time_boot_ms; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t com packet.alt_range_finder = alt_range_finder; packet.alt_extra = alt_extra; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDES_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ALTITUDES; - return mavlink_finalize_message(msg, system_id, component_id, 28, 55); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDES_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_ uint32_t time_boot_ms,int32_t alt_gps,int32_t alt_imu,int32_t alt_barometric,int32_t alt_optical_flow,int32_t alt_range_finder,int32_t alt_extra) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_ALTITUDES_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, alt_gps); _mav_put_int32_t(buf, 8, alt_imu); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_ _mav_put_int32_t(buf, 20, alt_range_finder); _mav_put_int32_t(buf, 24, alt_extra); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDES_LEN); #else mavlink_altitudes_t packet; packet.time_boot_ms = time_boot_ms; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_ packet.alt_range_finder = alt_range_finder; packet.alt_extra = alt_extra; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDES_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ALTITUDES; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 55); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDES_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_altitudes_encode(uint8_t system_id, uint8_t c static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_ALTITUDES_LEN]; _mav_put_uint32_t(buf, 0, time_boot_ms); _mav_put_int32_t(buf, 4, alt_gps); _mav_put_int32_t(buf, 8, alt_imu); @@ -164,7 +175,11 @@ static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t t _mav_put_int32_t(buf, 20, alt_range_finder); _mav_put_int32_t(buf, 24, alt_extra); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, 28, 55); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN); +#endif #else mavlink_altitudes_t packet; packet.time_boot_ms = time_boot_ms; @@ -175,7 +190,11 @@ static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t t packet.alt_range_finder = alt_range_finder; packet.alt_extra = alt_extra; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, 28, 55); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_altitudes_decode(const mavlink_message_t* msg, ma altitudes->alt_range_finder = mavlink_msg_altitudes_get_alt_range_finder(msg); altitudes->alt_extra = mavlink_msg_altitudes_get_alt_extra(msg); #else - memcpy(altitudes, _MAV_PAYLOAD(msg), 28); + memcpy(altitudes, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDES_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h index 1f1d88fa71aa86206c864ebba4f8bf8eb702af3b..d72a4dcacbf5b6aebd9f0db17e6e5979b914bd3f 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h @@ -16,6 +16,9 @@ typedef struct __mavlink_flexifunction_buffer_function_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN 58 #define MAVLINK_MSG_ID_152_LEN 58 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC 101 +#define MAVLINK_MSG_ID_152_CRC 101 + #define MAVLINK_MSG_FLEXIFUNCTION_BUFFER_FUNCTION_FIELD_DATA_LEN 48 #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_BUFFER_FUNCTION { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack(uint8_t sy uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[58]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN]; _mav_put_uint16_t(buf, 0, func_index); _mav_put_uint16_t(buf, 2, func_count); _mav_put_uint16_t(buf, 4, data_address); @@ -59,7 +62,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack(uint8_t sy _mav_put_uint8_t(buf, 8, target_system); _mav_put_uint8_t(buf, 9, target_component); _mav_put_int8_t_array(buf, 10, data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 58); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); #else mavlink_flexifunction_buffer_function_t packet; packet.func_index = func_index; @@ -69,11 +72,15 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack(uint8_t sy packet.target_system = target_system; packet.target_component = target_component; mav_array_memcpy(packet.data, data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 58); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION; - return mavlink_finalize_message(msg, system_id, component_id, 58, 101); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); +#endif } /** @@ -96,7 +103,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack_chan(uint8 uint8_t target_system,uint8_t target_component,uint16_t func_index,uint16_t func_count,uint16_t data_address,uint16_t data_size,const int8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[58]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN]; _mav_put_uint16_t(buf, 0, func_index); _mav_put_uint16_t(buf, 2, func_count); _mav_put_uint16_t(buf, 4, data_address); @@ -104,7 +111,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack_chan(uint8 _mav_put_uint8_t(buf, 8, target_system); _mav_put_uint8_t(buf, 9, target_component); _mav_put_int8_t_array(buf, 10, data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 58); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); #else mavlink_flexifunction_buffer_function_t packet; packet.func_index = func_index; @@ -114,11 +121,15 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack_chan(uint8 packet.target_system = target_system; packet.target_component = target_component; mav_array_memcpy(packet.data, data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 58); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 58, 101); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); +#endif } /** @@ -151,7 +162,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_encode(uint8_t static inline void mavlink_msg_flexifunction_buffer_function_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[58]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN]; _mav_put_uint16_t(buf, 0, func_index); _mav_put_uint16_t(buf, 2, func_count); _mav_put_uint16_t(buf, 4, data_address); @@ -159,7 +170,11 @@ static inline void mavlink_msg_flexifunction_buffer_function_send(mavlink_channe _mav_put_uint8_t(buf, 8, target_system); _mav_put_uint8_t(buf, 9, target_component); _mav_put_int8_t_array(buf, 10, data, 48); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, 58, 101); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); +#endif #else mavlink_flexifunction_buffer_function_t packet; packet.func_index = func_index; @@ -169,7 +184,11 @@ static inline void mavlink_msg_flexifunction_buffer_function_send(mavlink_channe packet.target_system = target_system; packet.target_component = target_component; mav_array_memcpy(packet.data, data, sizeof(int8_t)*48); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)&packet, 58, 101); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); +#endif #endif } @@ -265,6 +284,6 @@ static inline void mavlink_msg_flexifunction_buffer_function_decode(const mavlin flexifunction_buffer_function->target_component = mavlink_msg_flexifunction_buffer_function_get_target_component(msg); mavlink_msg_flexifunction_buffer_function_get_data(msg, flexifunction_buffer_function->data); #else - memcpy(flexifunction_buffer_function, _MAV_PAYLOAD(msg), 58); + memcpy(flexifunction_buffer_function, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h index dfbcc131315558a23c51e111ecfaa9120654d2a1..58f1786ef910acac730e3375e42cea12537e8a4a 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h @@ -13,6 +13,9 @@ typedef struct __mavlink_flexifunction_buffer_function_ack_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN 6 #define MAVLINK_MSG_ID_153_LEN 6 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC 109 +#define MAVLINK_MSG_ID_153_CRC 109 + #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_BUFFER_FUNCTION_ACK { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack(uint8_ uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN]; _mav_put_uint16_t(buf, 0, func_index); _mav_put_uint16_t(buf, 2, result); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); #else mavlink_flexifunction_buffer_function_ack_t packet; packet.func_index = func_index; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack(uint8_ packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 6, 109); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack_chan(u uint8_t target_system,uint8_t target_component,uint16_t func_index,uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN]; _mav_put_uint16_t(buf, 0, func_index); _mav_put_uint16_t(buf, 2, result); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); #else mavlink_flexifunction_buffer_function_ack_t packet; packet.func_index = func_index; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack_chan(u packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 109); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_encode(uint static inline void mavlink_msg_flexifunction_buffer_function_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN]; _mav_put_uint16_t(buf, 0, func_index); _mav_put_uint16_t(buf, 2, result); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, 6, 109); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); +#endif #else mavlink_flexifunction_buffer_function_ack_t packet; packet.func_index = func_index; @@ -142,7 +157,11 @@ static inline void mavlink_msg_flexifunction_buffer_function_ack_send(mavlink_ch packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)&packet, 6, 109); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_flexifunction_buffer_function_ack_decode(const ma flexifunction_buffer_function_ack->target_system = mavlink_msg_flexifunction_buffer_function_ack_get_target_system(msg); flexifunction_buffer_function_ack->target_component = mavlink_msg_flexifunction_buffer_function_ack_get_target_component(msg); #else - memcpy(flexifunction_buffer_function_ack, _MAV_PAYLOAD(msg), 6); + memcpy(flexifunction_buffer_function_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h index f60f9f0c529bd2854f8cd2b2e614948b418de230..2f6668cf95bc2a99b41b079f880a817e84b71311 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h @@ -12,6 +12,9 @@ typedef struct __mavlink_flexifunction_command_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN 3 #define MAVLINK_MSG_ID_157_LEN 3 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC 133 +#define MAVLINK_MSG_ID_157_CRC 133 + #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND { \ @@ -39,23 +42,27 @@ static inline uint16_t mavlink_msg_flexifunction_command_pack(uint8_t system_id, uint8_t target_system, uint8_t target_component, uint8_t command_type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, command_type); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); #else mavlink_flexifunction_command_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.command_type = command_type; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND; - return mavlink_finalize_message(msg, system_id, component_id, 3, 133); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); +#endif } /** @@ -74,23 +81,27 @@ static inline uint16_t mavlink_msg_flexifunction_command_pack_chan(uint8_t syste uint8_t target_system,uint8_t target_component,uint8_t command_type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, command_type); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); #else mavlink_flexifunction_command_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.command_type = command_type; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 133); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); +#endif } /** @@ -119,19 +130,27 @@ static inline uint16_t mavlink_msg_flexifunction_command_encode(uint8_t system_i static inline void mavlink_msg_flexifunction_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command_type) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[3]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, command_type); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, 3, 133); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); +#endif #else mavlink_flexifunction_command_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.command_type = command_type; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, 3, 133); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); +#endif #endif } @@ -183,6 +202,6 @@ static inline void mavlink_msg_flexifunction_command_decode(const mavlink_messag flexifunction_command->target_component = mavlink_msg_flexifunction_command_get_target_component(msg); flexifunction_command->command_type = mavlink_msg_flexifunction_command_get_command_type(msg); #else - memcpy(flexifunction_command, _MAV_PAYLOAD(msg), 3); + memcpy(flexifunction_command, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h index 97035de00ed3efa377cdd8d1983db9c875353336..4798febb01c76cd4430d6f98bd570bfbb5274b8c 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h @@ -11,6 +11,9 @@ typedef struct __mavlink_flexifunction_command_ack_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN 4 #define MAVLINK_MSG_ID_158_LEN 4 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC 208 +#define MAVLINK_MSG_ID_158_CRC 208 + #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND_ACK { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_flexifunction_command_ack_pack(uint8_t system uint16_t command_type, uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN]; _mav_put_uint16_t(buf, 0, command_type); _mav_put_uint16_t(buf, 2, result); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); #else mavlink_flexifunction_command_ack_t packet; packet.command_type = command_type; packet.result = result; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 4, 208); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_flexifunction_command_ack_pack_chan(uint8_t s uint16_t command_type,uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN]; _mav_put_uint16_t(buf, 0, command_type); _mav_put_uint16_t(buf, 2, result); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); #else mavlink_flexifunction_command_ack_t packet; packet.command_type = command_type; packet.result = result; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_flexifunction_command_ack_encode(uint8_t syst static inline void mavlink_msg_flexifunction_command_ack_send(mavlink_channel_t chan, uint16_t command_type, uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN]; _mav_put_uint16_t(buf, 0, command_type); _mav_put_uint16_t(buf, 2, result); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, 4, 208); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); +#endif #else mavlink_flexifunction_command_ack_t packet; packet.command_type = command_type; packet.result = result; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)&packet, 4, 208); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_flexifunction_command_ack_decode(const mavlink_me flexifunction_command_ack->command_type = mavlink_msg_flexifunction_command_ack_get_command_type(msg); flexifunction_command_ack->result = mavlink_msg_flexifunction_command_ack_get_result(msg); #else - memcpy(flexifunction_command_ack, _MAV_PAYLOAD(msg), 4); + memcpy(flexifunction_command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h index 0085b31edeb7a2726987387d8bdd0ac0eee2c1e8..947bfc591112f2140ccaa12153c0e7731d6c0822 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h @@ -15,6 +15,9 @@ typedef struct __mavlink_flexifunction_directory_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN 53 #define MAVLINK_MSG_ID_155_LEN 53 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC 12 +#define MAVLINK_MSG_ID_155_CRC 12 + #define MAVLINK_MSG_FLEXIFUNCTION_DIRECTORY_FIELD_DIRECTORY_DATA_LEN 48 #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_DIRECTORY { \ @@ -48,14 +51,14 @@ static inline uint16_t mavlink_msg_flexifunction_directory_pack(uint8_t system_i uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[53]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, directory_type); _mav_put_uint8_t(buf, 3, start_index); _mav_put_uint8_t(buf, 4, count); _mav_put_int8_t_array(buf, 5, directory_data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); #else mavlink_flexifunction_directory_t packet; packet.target_system = target_system; @@ -64,11 +67,15 @@ static inline uint16_t mavlink_msg_flexifunction_directory_pack(uint8_t system_i packet.start_index = start_index; packet.count = count; mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY; - return mavlink_finalize_message(msg, system_id, component_id, 53, 12); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); +#endif } /** @@ -90,14 +97,14 @@ static inline uint16_t mavlink_msg_flexifunction_directory_pack_chan(uint8_t sys uint8_t target_system,uint8_t target_component,uint8_t directory_type,uint8_t start_index,uint8_t count,const int8_t *directory_data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[53]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, directory_type); _mav_put_uint8_t(buf, 3, start_index); _mav_put_uint8_t(buf, 4, count); _mav_put_int8_t_array(buf, 5, directory_data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); #else mavlink_flexifunction_directory_t packet; packet.target_system = target_system; @@ -106,11 +113,15 @@ static inline uint16_t mavlink_msg_flexifunction_directory_pack_chan(uint8_t sys packet.start_index = start_index; packet.count = count; mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53, 12); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); +#endif } /** @@ -142,14 +153,18 @@ static inline uint16_t mavlink_msg_flexifunction_directory_encode(uint8_t system static inline void mavlink_msg_flexifunction_directory_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[53]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, directory_type); _mav_put_uint8_t(buf, 3, start_index); _mav_put_uint8_t(buf, 4, count); _mav_put_int8_t_array(buf, 5, directory_data, 48); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, 53, 12); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); +#endif #else mavlink_flexifunction_directory_t packet; packet.target_system = target_system; @@ -158,7 +173,11 @@ static inline void mavlink_msg_flexifunction_directory_send(mavlink_channel_t ch packet.start_index = start_index; packet.count = count; mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)&packet, 53, 12); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); +#endif #endif } @@ -243,6 +262,6 @@ static inline void mavlink_msg_flexifunction_directory_decode(const mavlink_mess flexifunction_directory->count = mavlink_msg_flexifunction_directory_get_count(msg); mavlink_msg_flexifunction_directory_get_directory_data(msg, flexifunction_directory->directory_data); #else - memcpy(flexifunction_directory, _MAV_PAYLOAD(msg), 53); + memcpy(flexifunction_directory, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h index 5112aa067feb2133fc7291442fb019984fbdd75d..5489dd6b5e19abcb5a8b8bca859964ac55d7a9eb 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h @@ -15,6 +15,9 @@ typedef struct __mavlink_flexifunction_directory_ack_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN 7 #define MAVLINK_MSG_ID_156_LEN 7 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC 218 +#define MAVLINK_MSG_ID_156_CRC 218 + #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_DIRECTORY_ACK { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack(uint8_t syst uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[7]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN]; _mav_put_uint16_t(buf, 0, result); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack(uint8_t syst _mav_put_uint8_t(buf, 5, start_index); _mav_put_uint8_t(buf, 6, count); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); #else mavlink_flexifunction_directory_ack_t packet; packet.result = result; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack(uint8_t syst packet.start_index = start_index; packet.count = count; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 7, 218); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack_chan(uint8_t uint8_t target_system,uint8_t target_component,uint8_t directory_type,uint8_t start_index,uint8_t count,uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[7]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN]; _mav_put_uint16_t(buf, 0, result); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack_chan(uint8_t _mav_put_uint8_t(buf, 5, start_index); _mav_put_uint8_t(buf, 6, count); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); #else mavlink_flexifunction_directory_ack_t packet; packet.result = result; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack_chan(uint8_t packet.start_index = start_index; packet.count = count; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 218); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_encode(uint8_t sy static inline void mavlink_msg_flexifunction_directory_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[7]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN]; _mav_put_uint16_t(buf, 0, result); _mav_put_uint8_t(buf, 2, target_system); _mav_put_uint8_t(buf, 3, target_component); @@ -154,7 +165,11 @@ static inline void mavlink_msg_flexifunction_directory_ack_send(mavlink_channel_ _mav_put_uint8_t(buf, 5, start_index); _mav_put_uint8_t(buf, 6, count); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, 7, 218); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); +#endif #else mavlink_flexifunction_directory_ack_t packet; packet.result = result; @@ -164,7 +179,11 @@ static inline void mavlink_msg_flexifunction_directory_ack_send(mavlink_channel_ packet.start_index = start_index; packet.count = count; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)&packet, 7, 218); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_flexifunction_directory_ack_decode(const mavlink_ flexifunction_directory_ack->start_index = mavlink_msg_flexifunction_directory_ack_get_start_index(msg); flexifunction_directory_ack->count = mavlink_msg_flexifunction_directory_ack_get_count(msg); #else - memcpy(flexifunction_directory_ack, _MAV_PAYLOAD(msg), 7); + memcpy(flexifunction_directory_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h index 431282420c4503786b9ed43bc39556c23633e1e9..9ffc2caa5f1ec045d2b565c0df720ae96e1468c8 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h @@ -13,6 +13,9 @@ typedef struct __mavlink_flexifunction_read_req_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN 6 #define MAVLINK_MSG_ID_151_LEN 6 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC 26 +#define MAVLINK_MSG_ID_151_CRC 26 + #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_READ_REQ { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_pack(uint8_t system_id uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN]; _mav_put_int16_t(buf, 0, read_req_type); _mav_put_int16_t(buf, 2, data_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); #else mavlink_flexifunction_read_req_t packet; packet.read_req_type = read_req_type; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_pack(uint8_t system_id packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ; - return mavlink_finalize_message(msg, system_id, component_id, 6, 26); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_pack_chan(uint8_t syst uint8_t target_system,uint8_t target_component,int16_t read_req_type,int16_t data_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN]; _mav_put_int16_t(buf, 0, read_req_type); _mav_put_int16_t(buf, 2, data_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); #else mavlink_flexifunction_read_req_t packet; packet.read_req_type = read_req_type; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_pack_chan(uint8_t syst packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 26); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_encode(uint8_t system_ static inline void mavlink_msg_flexifunction_read_req_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN]; _mav_put_int16_t(buf, 0, read_req_type); _mav_put_int16_t(buf, 2, data_index); _mav_put_uint8_t(buf, 4, target_system); _mav_put_uint8_t(buf, 5, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, 6, 26); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); +#endif #else mavlink_flexifunction_read_req_t packet; packet.read_req_type = read_req_type; @@ -142,7 +157,11 @@ static inline void mavlink_msg_flexifunction_read_req_send(mavlink_channel_t cha packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)&packet, 6, 26); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_flexifunction_read_req_decode(const mavlink_messa flexifunction_read_req->target_system = mavlink_msg_flexifunction_read_req_get_target_system(msg); flexifunction_read_req->target_component = mavlink_msg_flexifunction_read_req_get_target_component(msg); #else - memcpy(flexifunction_read_req, _MAV_PAYLOAD(msg), 6); + memcpy(flexifunction_read_req, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h index 021fcd10f9320536c9c00065e2f699b45210635a..fc7d1d2f8e6a9fba3e1beb892eaf6cf34768dba9 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h @@ -11,6 +11,9 @@ typedef struct __mavlink_flexifunction_set_t #define MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN 2 #define MAVLINK_MSG_ID_150_LEN 2 +#define MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC 181 +#define MAVLINK_MSG_ID_150_CRC 181 + #define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_SET { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_flexifunction_set_pack(uint8_t system_id, uin uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); #else mavlink_flexifunction_set_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_SET; - return mavlink_finalize_message(msg, system_id, component_id, 2, 181); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_flexifunction_set_pack_chan(uint8_t system_id uint8_t target_system,uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); #else mavlink_flexifunction_set_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_SET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 181); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_flexifunction_set_encode(uint8_t system_id, u static inline void mavlink_msg_flexifunction_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[2]; + char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN]; _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, 2, 181); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); +#endif #else mavlink_flexifunction_set_t packet; packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)&packet, 2, 181); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_flexifunction_set_decode(const mavlink_message_t* flexifunction_set->target_system = mavlink_msg_flexifunction_set_get_target_system(msg); flexifunction_set->target_component = mavlink_msg_flexifunction_set_get_target_component(msg); #else - memcpy(flexifunction_set, _MAV_PAYLOAD(msg), 2); + memcpy(flexifunction_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h index c06d23ef8434093b888ade631bb43d997ccf1732..df5645e765a2e6932357b960de998cc6d73158d5 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h @@ -13,6 +13,9 @@ typedef struct __mavlink_serial_udb_extra_f13_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN 14 #define MAVLINK_MSG_ID_177_LEN 14 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC 249 +#define MAVLINK_MSG_ID_177_CRC 249 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F13 { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack(uint8_t system_id, int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN]; _mav_put_int32_t(buf, 0, sue_lat_origin); _mav_put_int32_t(buf, 4, sue_lon_origin); _mav_put_int32_t(buf, 8, sue_alt_origin); _mav_put_int16_t(buf, 12, sue_week_no); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); #else mavlink_serial_udb_extra_f13_t packet; packet.sue_lat_origin = sue_lat_origin; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack(uint8_t system_id, packet.sue_alt_origin = sue_alt_origin; packet.sue_week_no = sue_week_no; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13; - return mavlink_finalize_message(msg, system_id, component_id, 14, 249); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack_chan(uint8_t system int16_t sue_week_no,int32_t sue_lat_origin,int32_t sue_lon_origin,int32_t sue_alt_origin) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN]; _mav_put_int32_t(buf, 0, sue_lat_origin); _mav_put_int32_t(buf, 4, sue_lon_origin); _mav_put_int32_t(buf, 8, sue_alt_origin); _mav_put_int16_t(buf, 12, sue_week_no); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); #else mavlink_serial_udb_extra_f13_t packet; packet.sue_lat_origin = sue_lat_origin; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack_chan(uint8_t system packet.sue_alt_origin = sue_alt_origin; packet.sue_week_no = sue_week_no; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 249); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_encode(uint8_t system_id static inline void mavlink_msg_serial_udb_extra_f13_send(mavlink_channel_t chan, int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[14]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN]; _mav_put_int32_t(buf, 0, sue_lat_origin); _mav_put_int32_t(buf, 4, sue_lon_origin); _mav_put_int32_t(buf, 8, sue_alt_origin); _mav_put_int16_t(buf, 12, sue_week_no); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, 14, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); +#endif #else mavlink_serial_udb_extra_f13_t packet; packet.sue_lat_origin = sue_lat_origin; @@ -142,7 +157,11 @@ static inline void mavlink_msg_serial_udb_extra_f13_send(mavlink_channel_t chan, packet.sue_alt_origin = sue_alt_origin; packet.sue_week_no = sue_week_no; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)&packet, 14, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_serial_udb_extra_f13_decode(const mavlink_message serial_udb_extra_f13->sue_alt_origin = mavlink_msg_serial_udb_extra_f13_get_sue_alt_origin(msg); serial_udb_extra_f13->sue_week_no = mavlink_msg_serial_udb_extra_f13_get_sue_week_no(msg); #else - memcpy(serial_udb_extra_f13, _MAV_PAYLOAD(msg), 14); + memcpy(serial_udb_extra_f13, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h index 4275b03d6cf93b771842c9cf92e9397977b0452d..5e38a590a46e159ab14e516de04423aaee846fca 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h @@ -20,6 +20,9 @@ typedef struct __mavlink_serial_udb_extra_f14_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN 17 #define MAVLINK_MSG_ID_178_LEN 17 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC 123 +#define MAVLINK_MSG_ID_178_CRC 123 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F14 { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack(uint8_t system_id, uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[17]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN]; _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); _mav_put_int16_t(buf, 4, sue_RCON); _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); @@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack(uint8_t system_id, _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); #else mavlink_serial_udb_extra_f14_t packet; packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE; @@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack(uint8_t system_id, packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14; - return mavlink_finalize_message(msg, system_id, component_id, 17, 123); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); +#endif } /** @@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack_chan(uint8_t system uint8_t sue_WIND_ESTIMATION,uint8_t sue_GPS_TYPE,uint8_t sue_DR,uint8_t sue_BOARD_TYPE,uint8_t sue_AIRFRAME,int16_t sue_RCON,int16_t sue_TRAP_FLAGS,uint32_t sue_TRAP_SOURCE,int16_t sue_osc_fail_count,uint8_t sue_CLOCK_CONFIG,uint8_t sue_FLIGHT_PLAN_TYPE) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[17]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN]; _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); _mav_put_int16_t(buf, 4, sue_RCON); _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); @@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack_chan(uint8_t system _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); #else mavlink_serial_udb_extra_f14_t packet; packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE; @@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack_chan(uint8_t system packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 123); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); +#endif } /** @@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_encode(uint8_t system_id static inline void mavlink_msg_serial_udb_extra_f14_send(mavlink_channel_t chan, uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[17]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN]; _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); _mav_put_int16_t(buf, 4, sue_RCON); _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); @@ -204,7 +215,11 @@ static inline void mavlink_msg_serial_udb_extra_f14_send(mavlink_channel_t chan, _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, 17, 123); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); +#endif #else mavlink_serial_udb_extra_f14_t packet; packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE; @@ -219,7 +234,11 @@ static inline void mavlink_msg_serial_udb_extra_f14_send(mavlink_channel_t chan, packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)&packet, 17, 123); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); +#endif #endif } @@ -359,6 +378,6 @@ static inline void mavlink_msg_serial_udb_extra_f14_decode(const mavlink_message serial_udb_extra_f14->sue_CLOCK_CONFIG = mavlink_msg_serial_udb_extra_f14_get_sue_CLOCK_CONFIG(msg); serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_FLIGHT_PLAN_TYPE(msg); #else - memcpy(serial_udb_extra_f14, _MAV_PAYLOAD(msg), 17); + memcpy(serial_udb_extra_f14, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h index f4ada7838cc975871b5e38a53370ef34c1df0fb4..8779b25ff5f5366307fab0af08baa500d9aac610 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h @@ -11,6 +11,9 @@ typedef struct __mavlink_serial_udb_extra_f15_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN 60 #define MAVLINK_MSG_ID_179_LEN 60 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC 7 +#define MAVLINK_MSG_ID_179_CRC 7 + #define MAVLINK_MSG_SERIAL_UDB_EXTRA_F15_FIELD_SUE_ID_VEHICLE_MODEL_NAME_LEN 40 #define MAVLINK_MSG_SERIAL_UDB_EXTRA_F15_FIELD_SUE_ID_VEHICLE_REGISTRATION_LEN 20 @@ -37,21 +40,25 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack(uint8_t system_id, const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[60]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN]; _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 60); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); #else mavlink_serial_udb_extra_f15_t packet; mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 60); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15; - return mavlink_finalize_message(msg, system_id, component_id, 60, 7); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); +#endif } /** @@ -69,21 +76,25 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack_chan(uint8_t system const uint8_t *sue_ID_VEHICLE_MODEL_NAME,const uint8_t *sue_ID_VEHICLE_REGISTRATION) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[60]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN]; _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 60); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); #else mavlink_serial_udb_extra_f15_t packet; mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 60); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 60, 7); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); +#endif } /** @@ -111,17 +122,25 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f15_encode(uint8_t system_id static inline void mavlink_msg_serial_udb_extra_f15_send(mavlink_channel_t chan, const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[60]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN]; _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, 60, 7); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); +#endif #else mavlink_serial_udb_extra_f15_t packet; mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)&packet, 60, 7); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); +#endif #endif } @@ -162,6 +181,6 @@ static inline void mavlink_msg_serial_udb_extra_f15_decode(const mavlink_message mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_MODEL_NAME(msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME); mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_REGISTRATION(msg, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION); #else - memcpy(serial_udb_extra_f15, _MAV_PAYLOAD(msg), 60); + memcpy(serial_udb_extra_f15, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h index 20cadbf27a3cb52fd18950411bda6e16b6adf075..1a173bfe448453ae80b853f6b60854062d3373ab 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h @@ -11,6 +11,9 @@ typedef struct __mavlink_serial_udb_extra_f16_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN 110 #define MAVLINK_MSG_ID_180_LEN 110 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC 222 +#define MAVLINK_MSG_ID_180_CRC 222 + #define MAVLINK_MSG_SERIAL_UDB_EXTRA_F16_FIELD_SUE_ID_LEAD_PILOT_LEN 40 #define MAVLINK_MSG_SERIAL_UDB_EXTRA_F16_FIELD_SUE_ID_DIY_DRONES_URL_LEN 70 @@ -37,21 +40,25 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack(uint8_t system_id, const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[110]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN]; _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); #else mavlink_serial_udb_extra_f16_t packet; mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16; - return mavlink_finalize_message(msg, system_id, component_id, 110, 222); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); +#endif } /** @@ -69,21 +76,25 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack_chan(uint8_t system const uint8_t *sue_ID_LEAD_PILOT,const uint8_t *sue_ID_DIY_DRONES_URL) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[110]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN]; _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); #else mavlink_serial_udb_extra_f16_t packet; mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 110, 222); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); +#endif } /** @@ -111,17 +122,25 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f16_encode(uint8_t system_id static inline void mavlink_msg_serial_udb_extra_f16_send(mavlink_channel_t chan, const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[110]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN]; _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, 110, 222); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); +#endif #else mavlink_serial_udb_extra_f16_t packet; mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)&packet, 110, 222); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); +#endif #endif } @@ -162,6 +181,6 @@ static inline void mavlink_msg_serial_udb_extra_f16_decode(const mavlink_message mavlink_msg_serial_udb_extra_f16_get_sue_ID_LEAD_PILOT(msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT); mavlink_msg_serial_udb_extra_f16_get_sue_ID_DIY_DRONES_URL(msg, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL); #else - memcpy(serial_udb_extra_f16, _MAV_PAYLOAD(msg), 110); + memcpy(serial_udb_extra_f16, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h index 30d0cb845290688a78a7c3c23adcdc8d62721008..ddfc236ba40aa69f3713e991f76994005aa769dd 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h @@ -37,6 +37,9 @@ typedef struct __mavlink_serial_udb_extra_f2_a_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN 63 #define MAVLINK_MSG_ID_170_LEN 63 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC 150 +#define MAVLINK_MSG_ID_170_CRC 150 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F2_A { \ @@ -114,7 +117,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack(uint8_t system_id, uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[63]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN]; _mav_put_uint32_t(buf, 0, sue_time); _mav_put_int32_t(buf, 4, sue_latitude); _mav_put_int32_t(buf, 8, sue_longitude); @@ -144,7 +147,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack(uint8_t system_id, _mav_put_int16_t(buf, 60, sue_hdop); _mav_put_uint8_t(buf, 62, sue_status); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 63); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); #else mavlink_serial_udb_extra_f2_a_t packet; packet.sue_time = sue_time; @@ -176,11 +179,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack(uint8_t system_id, packet.sue_hdop = sue_hdop; packet.sue_status = sue_status; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 63); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A; - return mavlink_finalize_message(msg, system_id, component_id, 63, 150); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); +#endif } /** @@ -224,7 +231,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack_chan(uint8_t syste uint32_t sue_time,uint8_t sue_status,int32_t sue_latitude,int32_t sue_longitude,int32_t sue_altitude,uint16_t sue_waypoint_index,int16_t sue_rmat0,int16_t sue_rmat1,int16_t sue_rmat2,int16_t sue_rmat3,int16_t sue_rmat4,int16_t sue_rmat5,int16_t sue_rmat6,int16_t sue_rmat7,int16_t sue_rmat8,uint16_t sue_cog,int16_t sue_sog,uint16_t sue_cpu_load,int16_t sue_voltage_milis,uint16_t sue_air_speed_3DIMU,int16_t sue_estimated_wind_0,int16_t sue_estimated_wind_1,int16_t sue_estimated_wind_2,int16_t sue_magFieldEarth0,int16_t sue_magFieldEarth1,int16_t sue_magFieldEarth2,int16_t sue_svs,int16_t sue_hdop) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[63]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN]; _mav_put_uint32_t(buf, 0, sue_time); _mav_put_int32_t(buf, 4, sue_latitude); _mav_put_int32_t(buf, 8, sue_longitude); @@ -254,7 +261,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack_chan(uint8_t syste _mav_put_int16_t(buf, 60, sue_hdop); _mav_put_uint8_t(buf, 62, sue_status); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 63); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); #else mavlink_serial_udb_extra_f2_a_t packet; packet.sue_time = sue_time; @@ -286,11 +293,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack_chan(uint8_t syste packet.sue_hdop = sue_hdop; packet.sue_status = sue_status; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 63); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 63, 150); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); +#endif } /** @@ -344,7 +355,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_encode(uint8_t system_i static inline void mavlink_msg_serial_udb_extra_f2_a_send(mavlink_channel_t chan, uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[63]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN]; _mav_put_uint32_t(buf, 0, sue_time); _mav_put_int32_t(buf, 4, sue_latitude); _mav_put_int32_t(buf, 8, sue_longitude); @@ -374,7 +385,11 @@ static inline void mavlink_msg_serial_udb_extra_f2_a_send(mavlink_channel_t chan _mav_put_int16_t(buf, 60, sue_hdop); _mav_put_uint8_t(buf, 62, sue_status); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, 63, 150); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); +#endif #else mavlink_serial_udb_extra_f2_a_t packet; packet.sue_time = sue_time; @@ -406,7 +421,11 @@ static inline void mavlink_msg_serial_udb_extra_f2_a_send(mavlink_channel_t chan packet.sue_hdop = sue_hdop; packet.sue_status = sue_status; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)&packet, 63, 150); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); +#endif #endif } @@ -733,6 +752,6 @@ static inline void mavlink_msg_serial_udb_extra_f2_a_decode(const mavlink_messag serial_udb_extra_f2_a->sue_hdop = mavlink_msg_serial_udb_extra_f2_a_get_sue_hdop(msg); serial_udb_extra_f2_a->sue_status = mavlink_msg_serial_udb_extra_f2_a_get_sue_status(msg); #else - memcpy(serial_udb_extra_f2_a, _MAV_PAYLOAD(msg), 63); + memcpy(serial_udb_extra_f2_a, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h index 7f0c8fe0a076583964a989df562652395924e919..74da8416d86ea355bfb714b3e0a637f7ce14d1ab 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h @@ -42,6 +42,9 @@ typedef struct __mavlink_serial_udb_extra_f2_b_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN 70 #define MAVLINK_MSG_ID_171_LEN 70 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC 169 +#define MAVLINK_MSG_ID_171_CRC 169 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F2_B { \ @@ -129,7 +132,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack(uint8_t system_id, uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[70]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN]; _mav_put_uint32_t(buf, 0, sue_time); _mav_put_uint32_t(buf, 4, sue_flags); _mav_put_int16_t(buf, 8, sue_pwm_input_1); @@ -164,7 +167,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack(uint8_t system_id, _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); _mav_put_int16_t(buf, 68, sue_memory_stack_free); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); #else mavlink_serial_udb_extra_f2_b_t packet; packet.sue_time = sue_time; @@ -201,11 +204,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack(uint8_t system_id, packet.sue_waypoint_goal_z = sue_waypoint_goal_z; packet.sue_memory_stack_free = sue_memory_stack_free; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B; - return mavlink_finalize_message(msg, system_id, component_id, 70, 169); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); +#endif } /** @@ -254,7 +261,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack_chan(uint8_t syste uint32_t sue_time,int16_t sue_pwm_input_1,int16_t sue_pwm_input_2,int16_t sue_pwm_input_3,int16_t sue_pwm_input_4,int16_t sue_pwm_input_5,int16_t sue_pwm_input_6,int16_t sue_pwm_input_7,int16_t sue_pwm_input_8,int16_t sue_pwm_input_9,int16_t sue_pwm_input_10,int16_t sue_pwm_output_1,int16_t sue_pwm_output_2,int16_t sue_pwm_output_3,int16_t sue_pwm_output_4,int16_t sue_pwm_output_5,int16_t sue_pwm_output_6,int16_t sue_pwm_output_7,int16_t sue_pwm_output_8,int16_t sue_pwm_output_9,int16_t sue_pwm_output_10,int16_t sue_imu_location_x,int16_t sue_imu_location_y,int16_t sue_imu_location_z,uint32_t sue_flags,int16_t sue_osc_fails,int16_t sue_imu_velocity_x,int16_t sue_imu_velocity_y,int16_t sue_imu_velocity_z,int16_t sue_waypoint_goal_x,int16_t sue_waypoint_goal_y,int16_t sue_waypoint_goal_z,int16_t sue_memory_stack_free) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[70]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN]; _mav_put_uint32_t(buf, 0, sue_time); _mav_put_uint32_t(buf, 4, sue_flags); _mav_put_int16_t(buf, 8, sue_pwm_input_1); @@ -289,7 +296,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack_chan(uint8_t syste _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); _mav_put_int16_t(buf, 68, sue_memory_stack_free); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); #else mavlink_serial_udb_extra_f2_b_t packet; packet.sue_time = sue_time; @@ -326,11 +333,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack_chan(uint8_t syste packet.sue_waypoint_goal_z = sue_waypoint_goal_z; packet.sue_memory_stack_free = sue_memory_stack_free; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 70, 169); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); +#endif } /** @@ -389,7 +400,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_encode(uint8_t system_i static inline void mavlink_msg_serial_udb_extra_f2_b_send(mavlink_channel_t chan, uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[70]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN]; _mav_put_uint32_t(buf, 0, sue_time); _mav_put_uint32_t(buf, 4, sue_flags); _mav_put_int16_t(buf, 8, sue_pwm_input_1); @@ -424,7 +435,11 @@ static inline void mavlink_msg_serial_udb_extra_f2_b_send(mavlink_channel_t chan _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); _mav_put_int16_t(buf, 68, sue_memory_stack_free); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, 70, 169); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); +#endif #else mavlink_serial_udb_extra_f2_b_t packet; packet.sue_time = sue_time; @@ -461,7 +476,11 @@ static inline void mavlink_msg_serial_udb_extra_f2_b_send(mavlink_channel_t chan packet.sue_waypoint_goal_z = sue_waypoint_goal_z; packet.sue_memory_stack_free = sue_memory_stack_free; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)&packet, 70, 169); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); +#endif #endif } @@ -843,6 +862,6 @@ static inline void mavlink_msg_serial_udb_extra_f2_b_decode(const mavlink_messag serial_udb_extra_f2_b->sue_waypoint_goal_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_z(msg); serial_udb_extra_f2_b->sue_memory_stack_free = mavlink_msg_serial_udb_extra_f2_b_get_sue_memory_stack_free(msg); #else - memcpy(serial_udb_extra_f2_b, _MAV_PAYLOAD(msg), 70); + memcpy(serial_udb_extra_f2_b, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h index 90c8e042887f6c6531ebe2f80572d93d83049e0d..83ccbbedb4857a57f3fa64700cfd3884780c0d26 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h @@ -19,6 +19,9 @@ typedef struct __mavlink_serial_udb_extra_f4_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN 10 #define MAVLINK_MSG_ID_172_LEN 10 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC 191 +#define MAVLINK_MSG_ID_172_CRC 191 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F4 { \ @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack(uint8_t system_id, u uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[10]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN]; _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); @@ -72,7 +75,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack(uint8_t system_id, u _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); #else mavlink_serial_udb_extra_f4_t packet; packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; @@ -86,11 +89,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack(uint8_t system_id, u packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; packet.sue_RACING_MODE = sue_RACING_MODE; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4; - return mavlink_finalize_message(msg, system_id, component_id, 10, 191); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); +#endif } /** @@ -116,7 +123,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack_chan(uint8_t system_ uint8_t sue_ROLL_STABILIZATION_AILERONS,uint8_t sue_ROLL_STABILIZATION_RUDDER,uint8_t sue_PITCH_STABILIZATION,uint8_t sue_YAW_STABILIZATION_RUDDER,uint8_t sue_YAW_STABILIZATION_AILERON,uint8_t sue_AILERON_NAVIGATION,uint8_t sue_RUDDER_NAVIGATION,uint8_t sue_ALTITUDEHOLD_STABILIZED,uint8_t sue_ALTITUDEHOLD_WAYPOINT,uint8_t sue_RACING_MODE) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[10]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN]; _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack_chan(uint8_t system_ _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); #else mavlink_serial_udb_extra_f4_t packet; packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; @@ -142,11 +149,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack_chan(uint8_t system_ packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; packet.sue_RACING_MODE = sue_RACING_MODE; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 10, 191); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); +#endif } /** @@ -182,7 +193,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_encode(uint8_t system_id, static inline void mavlink_msg_serial_udb_extra_f4_send(mavlink_channel_t chan, uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[10]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN]; _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); @@ -194,7 +205,11 @@ static inline void mavlink_msg_serial_udb_extra_f4_send(mavlink_channel_t chan, _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, 10, 191); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); +#endif #else mavlink_serial_udb_extra_f4_t packet; packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; @@ -208,7 +223,11 @@ static inline void mavlink_msg_serial_udb_extra_f4_send(mavlink_channel_t chan, packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; packet.sue_RACING_MODE = sue_RACING_MODE; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)&packet, 10, 191); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); +#endif #endif } @@ -337,6 +356,6 @@ static inline void mavlink_msg_serial_udb_extra_f4_decode(const mavlink_message_ serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT = mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_WAYPOINT(msg); serial_udb_extra_f4->sue_RACING_MODE = mavlink_msg_serial_udb_extra_f4_get_sue_RACING_MODE(msg); #else - memcpy(serial_udb_extra_f4, _MAV_PAYLOAD(msg), 10); + memcpy(serial_udb_extra_f4, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h index 79db8f1d82555aaadfdeb0a1d80ac2bd66c50c3b..2b2451f00d707e773bc7827592a09b041b155fcb 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h @@ -15,6 +15,9 @@ typedef struct __mavlink_serial_udb_extra_f5_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN 24 #define MAVLINK_MSG_ID_173_LEN 24 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC 121 +#define MAVLINK_MSG_ID_173_CRC 121 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F5 { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, u float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN]; _mav_put_float(buf, 0, sue_YAWKP_AILERON); _mav_put_float(buf, 4, sue_YAWKD_AILERON); _mav_put_float(buf, 8, sue_ROLLKP); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, u _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); _mav_put_float(buf, 20, sue_AILERON_BOOST); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); #else mavlink_serial_udb_extra_f5_t packet; packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, u packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; packet.sue_AILERON_BOOST = sue_AILERON_BOOST; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5; - return mavlink_finalize_message(msg, system_id, component_id, 24, 121); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_ float sue_YAWKP_AILERON,float sue_YAWKD_AILERON,float sue_ROLLKP,float sue_ROLLKD,float sue_YAW_STABILIZATION_AILERON,float sue_AILERON_BOOST) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN]; _mav_put_float(buf, 0, sue_YAWKP_AILERON); _mav_put_float(buf, 4, sue_YAWKD_AILERON); _mav_put_float(buf, 8, sue_ROLLKP); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_ _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); _mav_put_float(buf, 20, sue_AILERON_BOOST); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); #else mavlink_serial_udb_extra_f5_t packet; packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_ packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; packet.sue_AILERON_BOOST = sue_AILERON_BOOST; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 121); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode(uint8_t system_id, static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN]; _mav_put_float(buf, 0, sue_YAWKP_AILERON); _mav_put_float(buf, 4, sue_YAWKD_AILERON); _mav_put_float(buf, 8, sue_ROLLKP); @@ -154,7 +165,11 @@ static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan, _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); _mav_put_float(buf, 20, sue_AILERON_BOOST); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, 24, 121); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); +#endif #else mavlink_serial_udb_extra_f5_t packet; packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON; @@ -164,7 +179,11 @@ static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan, packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; packet.sue_AILERON_BOOST = sue_AILERON_BOOST; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, 24, 121); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_serial_udb_extra_f5_decode(const mavlink_message_ serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(msg); serial_udb_extra_f5->sue_AILERON_BOOST = mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(msg); #else - memcpy(serial_udb_extra_f5, _MAV_PAYLOAD(msg), 24); + memcpy(serial_udb_extra_f5, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h index 744866affe8af8bbe5677909dbcac46aff57ccdd..9d58ca9a8e170d8c8831fc1e6727cc505017e342 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h @@ -14,6 +14,9 @@ typedef struct __mavlink_serial_udb_extra_f6_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN 20 #define MAVLINK_MSG_ID_174_LEN 20 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC 54 +#define MAVLINK_MSG_ID_174_CRC 54 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F6 { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack(uint8_t system_id, u float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN]; _mav_put_float(buf, 0, sue_PITCHGAIN); _mav_put_float(buf, 4, sue_PITCHKD); _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); #else mavlink_serial_udb_extra_f6_t packet; packet.sue_PITCHGAIN = sue_PITCHGAIN; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack(uint8_t system_id, u packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6; - return mavlink_finalize_message(msg, system_id, component_id, 20, 54); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack_chan(uint8_t system_ float sue_PITCHGAIN,float sue_PITCHKD,float sue_RUDDER_ELEV_MIX,float sue_ROLL_ELEV_MIX,float sue_ELEVATOR_BOOST) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN]; _mav_put_float(buf, 0, sue_PITCHGAIN); _mav_put_float(buf, 4, sue_PITCHKD); _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); #else mavlink_serial_udb_extra_f6_t packet; packet.sue_PITCHGAIN = sue_PITCHGAIN; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack_chan(uint8_t system_ packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 54); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_encode(uint8_t system_id, static inline void mavlink_msg_serial_udb_extra_f6_send(mavlink_channel_t chan, float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN]; _mav_put_float(buf, 0, sue_PITCHGAIN); _mav_put_float(buf, 4, sue_PITCHKD); _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, 20, 54); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); +#endif #else mavlink_serial_udb_extra_f6_t packet; packet.sue_PITCHGAIN = sue_PITCHGAIN; @@ -153,7 +168,11 @@ static inline void mavlink_msg_serial_udb_extra_f6_send(mavlink_channel_t chan, packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)&packet, 20, 54); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_serial_udb_extra_f6_decode(const mavlink_message_ serial_udb_extra_f6->sue_ROLL_ELEV_MIX = mavlink_msg_serial_udb_extra_f6_get_sue_ROLL_ELEV_MIX(msg); serial_udb_extra_f6->sue_ELEVATOR_BOOST = mavlink_msg_serial_udb_extra_f6_get_sue_ELEVATOR_BOOST(msg); #else - memcpy(serial_udb_extra_f6, _MAV_PAYLOAD(msg), 20); + memcpy(serial_udb_extra_f6, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h index 744ce0db0e04865dacfd02d9e2e5dd66ba1eb581..ab73b967e07c3619d7fa7b3411fa39e5b02e37f3 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h @@ -15,6 +15,9 @@ typedef struct __mavlink_serial_udb_extra_f7_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN 24 #define MAVLINK_MSG_ID_175_LEN 24 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC 171 +#define MAVLINK_MSG_ID_175_CRC 171 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F7 { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack(uint8_t system_id, u float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN]; _mav_put_float(buf, 0, sue_YAWKP_RUDDER); _mav_put_float(buf, 4, sue_YAWKD_RUDDER); _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack(uint8_t system_id, u _mav_put_float(buf, 16, sue_RUDDER_BOOST); _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); #else mavlink_serial_udb_extra_f7_t packet; packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack(uint8_t system_id, u packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST; packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7; - return mavlink_finalize_message(msg, system_id, component_id, 24, 171); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack_chan(uint8_t system_ float sue_YAWKP_RUDDER,float sue_YAWKD_RUDDER,float sue_ROLLKP_RUDDER,float sue_ROLLKD_RUDDER,float sue_RUDDER_BOOST,float sue_RTL_PITCH_DOWN) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN]; _mav_put_float(buf, 0, sue_YAWKP_RUDDER); _mav_put_float(buf, 4, sue_YAWKD_RUDDER); _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack_chan(uint8_t system_ _mav_put_float(buf, 16, sue_RUDDER_BOOST); _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); #else mavlink_serial_udb_extra_f7_t packet; packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack_chan(uint8_t system_ packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST; packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 171); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_encode(uint8_t system_id, static inline void mavlink_msg_serial_udb_extra_f7_send(mavlink_channel_t chan, float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN]; _mav_put_float(buf, 0, sue_YAWKP_RUDDER); _mav_put_float(buf, 4, sue_YAWKD_RUDDER); _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); @@ -154,7 +165,11 @@ static inline void mavlink_msg_serial_udb_extra_f7_send(mavlink_channel_t chan, _mav_put_float(buf, 16, sue_RUDDER_BOOST); _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, 24, 171); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); +#endif #else mavlink_serial_udb_extra_f7_t packet; packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; @@ -164,7 +179,11 @@ static inline void mavlink_msg_serial_udb_extra_f7_send(mavlink_channel_t chan, packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST; packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)&packet, 24, 171); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_serial_udb_extra_f7_decode(const mavlink_message_ serial_udb_extra_f7->sue_RUDDER_BOOST = mavlink_msg_serial_udb_extra_f7_get_sue_RUDDER_BOOST(msg); serial_udb_extra_f7->sue_RTL_PITCH_DOWN = mavlink_msg_serial_udb_extra_f7_get_sue_RTL_PITCH_DOWN(msg); #else - memcpy(serial_udb_extra_f7, _MAV_PAYLOAD(msg), 24); + memcpy(serial_udb_extra_f7, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h index c92630e0375610e169588676dd611ba9ff315ed5..310246e8e72777b1934fe0005fbf991cda3bc3c6 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h @@ -16,6 +16,9 @@ typedef struct __mavlink_serial_udb_extra_f8_t #define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN 28 #define MAVLINK_MSG_ID_176_LEN 28 +#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC 142 +#define MAVLINK_MSG_ID_176_CRC 142 + #define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F8 { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack(uint8_t system_id, u float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN]; _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack(uint8_t system_id, u _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); #else mavlink_serial_udb_extra_f8_t packet; packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack(uint8_t system_id, u packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8; - return mavlink_finalize_message(msg, system_id, component_id, 28, 142); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack_chan(uint8_t system_ float sue_HEIGHT_TARGET_MAX,float sue_HEIGHT_TARGET_MIN,float sue_ALT_HOLD_THROTTLE_MIN,float sue_ALT_HOLD_THROTTLE_MAX,float sue_ALT_HOLD_PITCH_MIN,float sue_ALT_HOLD_PITCH_MAX,float sue_ALT_HOLD_PITCH_HIGH) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN]; _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack_chan(uint8_t system_ _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); #else mavlink_serial_udb_extra_f8_t packet; packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack_chan(uint8_t system_ packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 142); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_encode(uint8_t system_id, static inline void mavlink_msg_serial_udb_extra_f8_send(mavlink_channel_t chan, float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[28]; + char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN]; _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); @@ -164,7 +175,11 @@ static inline void mavlink_msg_serial_udb_extra_f8_send(mavlink_channel_t chan, _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, 28, 142); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); +#endif #else mavlink_serial_udb_extra_f8_t packet; packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; @@ -175,7 +190,11 @@ static inline void mavlink_msg_serial_udb_extra_f8_send(mavlink_channel_t chan, packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)&packet, 28, 142); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_serial_udb_extra_f8_decode(const mavlink_message_ serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MAX(msg); serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_HIGH(msg); #else - memcpy(serial_udb_extra_f8, _MAV_PAYLOAD(msg), 28); + memcpy(serial_udb_extra_f8, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/matrixpilot/version.h b/libs/mavlink/include/mavlink/v1.0/matrixpilot/version.h index 7d9e1eafdbd32fbff604c307c8b32b14b5f14324..6384ed6a926a0d826fd1c6c44de63aa6e60ec385 100644 --- a/libs/mavlink/include/mavlink/v1.0/matrixpilot/version.h +++ b/libs/mavlink/include/mavlink/v1.0/matrixpilot/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Wed Jan 9 16:18:08 2013" +#define MAVLINK_BUILD_DATE "Fri Jun 7 22:44:10 2013" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254 diff --git a/libs/mavlink/include/mavlink/v1.0/mavlink_types.h b/libs/mavlink/include/mavlink/v1.0/mavlink_types.h index 704e77f81fc4783372631bb701a3f3bcf3a69e67..6724e49f1d69de368456d3a8e4ed5f338c9ec834 100644 --- a/libs/mavlink/include/mavlink/v1.0/mavlink_types.h +++ b/libs/mavlink/include/mavlink/v1.0/mavlink_types.h @@ -33,10 +33,11 @@ typedef struct param_union { float param_float; int32_t param_int32; uint32_t param_uint32; - uint8_t param_uint8; - uint8_t bytes[4]; int16_t param_int16; + uint16_t param_uint16; int8_t param_int8; + uint8_t param_uint8; + uint8_t bytes[4]; }; uint8_t type; } mavlink_param_union_t; diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h index 819c45bf27307d395e8e0f9d074e7d13e7495135..1aac8395dfad3cd2c006afdd2c2cb6923e8177c3 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h @@ -18,6 +18,9 @@ typedef struct __mavlink_attitude_control_t #define MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN 21 #define MAVLINK_MSG_ID_200_LEN 21 +#define MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC 254 +#define MAVLINK_MSG_ID_200_CRC 254 + #define MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL { \ @@ -57,7 +60,7 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[21]; + char buf[MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -68,7 +71,7 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); #else mavlink_attitude_control_t packet; packet.roll = roll; @@ -81,11 +84,15 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 21, 254); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); +#endif } /** @@ -110,7 +117,7 @@ static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[21]; + char buf[MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -121,7 +128,7 @@ static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); #else mavlink_attitude_control_t packet; packet.roll = roll; @@ -134,11 +141,15 @@ static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 254); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); +#endif } /** @@ -173,7 +184,7 @@ static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, ui static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[21]; + char buf[MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN]; _mav_put_float(buf, 0, roll); _mav_put_float(buf, 4, pitch); _mav_put_float(buf, 8, yaw); @@ -184,7 +195,11 @@ static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uin _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, 21, 254); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); +#endif #else mavlink_attitude_control_t packet; packet.roll = roll; @@ -197,7 +212,11 @@ static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uin packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, 21, 254); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); +#endif #endif } @@ -315,6 +334,6 @@ static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg); attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg); #else - memcpy(attitude_control, _MAV_PAYLOAD(msg), 21); + memcpy(attitude_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h index cde782b484963c2d72cc59ca49e5d45d3778a24f..353e105814c2e09b7f7102d994809a2b6722b68b 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h @@ -17,6 +17,9 @@ typedef struct __mavlink_brief_feature_t #define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN 53 #define MAVLINK_MSG_ID_195_LEN 53 +#define MAVLINK_MSG_ID_BRIEF_FEATURE_CRC 88 +#define MAVLINK_MSG_ID_195_CRC 88 + #define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32 #define MAVLINK_MESSAGE_INFO_BRIEF_FEATURE { \ @@ -54,7 +57,7 @@ static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[53]; + char buf[MAVLINK_MSG_ID_BRIEF_FEATURE_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t _mav_put_uint16_t(buf, 18, orientation); _mav_put_uint8_t(buf, 20, orientation_assignment); _mav_put_uint8_t_array(buf, 21, descriptor, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); #else mavlink_brief_feature_t packet; packet.x = x; @@ -74,11 +77,15 @@ static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t packet.orientation = orientation; packet.orientation_assignment = orientation_assignment; mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; - return mavlink_finalize_message(msg, system_id, component_id, 53, 88); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); +#endif } /** @@ -102,7 +109,7 @@ static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, ui float x,float y,float z,uint8_t orientation_assignment,uint16_t size,uint16_t orientation,const uint8_t *descriptor,float response) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[53]; + char buf[MAVLINK_MSG_ID_BRIEF_FEATURE_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -111,7 +118,7 @@ static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, ui _mav_put_uint16_t(buf, 18, orientation); _mav_put_uint8_t(buf, 20, orientation_assignment); _mav_put_uint8_t_array(buf, 21, descriptor, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); #else mavlink_brief_feature_t packet; packet.x = x; @@ -122,11 +129,15 @@ static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, ui packet.orientation = orientation; packet.orientation_assignment = orientation_assignment; mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53, 88); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); +#endif } /** @@ -160,7 +171,7 @@ static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8 static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[53]; + char buf[MAVLINK_MSG_ID_BRIEF_FEATURE_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -169,7 +180,11 @@ static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float _mav_put_uint16_t(buf, 18, orientation); _mav_put_uint8_t(buf, 20, orientation_assignment); _mav_put_uint8_t_array(buf, 21, descriptor, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, 53, 88); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); +#endif #else mavlink_brief_feature_t packet; packet.x = x; @@ -180,7 +195,11 @@ static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float packet.orientation = orientation; packet.orientation_assignment = orientation_assignment; mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, 53, 88); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); +#endif #endif } @@ -287,6 +306,6 @@ static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg); mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor); #else - memcpy(brief_feature, _MAV_PAYLOAD(msg), 53); + memcpy(brief_feature, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h index d3ca73f12d59afeb97f3e9371d58931eaf213ab4..5251c35c326b64650c1ef8649fcf856d2944b6b0 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h @@ -16,6 +16,9 @@ typedef struct __mavlink_data_transmission_handshake_t #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 12 #define MAVLINK_MSG_ID_193_LEN 12 +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 23 +#define MAVLINK_MSG_ID_193_CRC 23 + #define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint8_t packets, uint8_t payload, uint8_t jpg_quality) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; _mav_put_uint32_t(buf, 0, size); _mav_put_uint16_t(buf, 4, width); _mav_put_uint16_t(buf, 6, height); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst _mav_put_uint8_t(buf, 10, payload); _mav_put_uint8_t(buf, 11, jpg_quality); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); #else mavlink_data_transmission_handshake_t packet; packet.size = size; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst packet.payload = payload; packet.jpg_quality = jpg_quality; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; - return mavlink_finalize_message(msg, system_id, component_id, 12, 23); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint8_t packets,uint8_t payload,uint8_t jpg_quality) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; _mav_put_uint32_t(buf, 0, size); _mav_put_uint16_t(buf, 4, width); _mav_put_uint16_t(buf, 6, height); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t _mav_put_uint8_t(buf, 10, payload); _mav_put_uint8_t(buf, 11, jpg_quality); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); #else mavlink_data_transmission_handshake_t packet; packet.size = size; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t packet.payload = payload; packet.jpg_quality = jpg_quality; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 23); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t sy static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint8_t packets, uint8_t payload, uint8_t jpg_quality) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; _mav_put_uint32_t(buf, 0, size); _mav_put_uint16_t(buf, 4, width); _mav_put_uint16_t(buf, 6, height); @@ -164,7 +175,11 @@ static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_ _mav_put_uint8_t(buf, 10, payload); _mav_put_uint8_t(buf, 11, jpg_quality); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, 12, 23); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif #else mavlink_data_transmission_handshake_t packet; packet.size = size; @@ -175,7 +190,11 @@ static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_ packet.payload = payload; packet.jpg_quality = jpg_quality; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, 12, 23); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_ data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); #else - memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), 12); + memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h index e07be29528e02260d2a212b6c7f193fe5f337d2c..feeef6f39883873188ed6605faf375de92ad8d24 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h @@ -11,6 +11,9 @@ typedef struct __mavlink_encapsulated_data_t #define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 #define MAVLINK_MSG_ID_194_LEN 255 +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 +#define MAVLINK_MSG_ID_194_CRC 223 + #define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 #define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ @@ -36,19 +39,23 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uin uint16_t seqnr, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[255]; + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; _mav_put_uint16_t(buf, 0, seqnr); _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); #else mavlink_encapsulated_data_t packet; packet.seqnr = seqnr; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message(msg, system_id, component_id, 255, 223); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif } /** @@ -66,19 +73,23 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id uint16_t seqnr,const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[255]; + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; _mav_put_uint16_t(buf, 0, seqnr); _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); #else mavlink_encapsulated_data_t packet; packet.seqnr = seqnr; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); #endif msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255, 223); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif } /** @@ -106,15 +117,23 @@ static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, u static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[255]; + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; _mav_put_uint16_t(buf, 0, seqnr); _mav_put_uint8_t_array(buf, 2, data, 253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, 255, 223); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif #else mavlink_encapsulated_data_t packet; packet.seqnr = seqnr; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, 255, 223); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif #endif } @@ -155,6 +174,6 @@ static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); #else - memcpy(encapsulated_data, _MAV_PAYLOAD(msg), 255); + memcpy(encapsulated_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h index 913fcd94c15636c5d0a2c3b436fb2fd51350875a..6d1d9cca7621b1f02380ec7dad503f53f5cbf74a 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h @@ -32,6 +32,9 @@ typedef struct __mavlink_image_available_t #define MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN 92 #define MAVLINK_MSG_ID_154_LEN 92 +#define MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC 224 +#define MAVLINK_MSG_ID_154_CRC 224 + #define MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE { \ @@ -99,7 +102,7 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[92]; + char buf[MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN]; _mav_put_uint64_t(buf, 0, cam_id); _mav_put_uint64_t(buf, 8, timestamp); _mav_put_uint64_t(buf, 16, valid_until); @@ -124,7 +127,7 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 90, cam_no); _mav_put_uint8_t(buf, 91, channels); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 92); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); #else mavlink_image_available_t packet; packet.cam_id = cam_id; @@ -151,11 +154,15 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 packet.cam_no = cam_no; packet.channels = channels; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 92); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; - return mavlink_finalize_message(msg, system_id, component_id, 92, 224); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); +#endif } /** @@ -194,7 +201,7 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, 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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[92]; + char buf[MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN]; _mav_put_uint64_t(buf, 0, cam_id); _mav_put_uint64_t(buf, 8, timestamp); _mav_put_uint64_t(buf, 16, valid_until); @@ -219,7 +226,7 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 90, cam_no); _mav_put_uint8_t(buf, 91, channels); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 92); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); #else mavlink_image_available_t packet; packet.cam_id = cam_id; @@ -246,11 +253,15 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, packet.cam_no = cam_no; packet.channels = channels; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 92); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 92, 224); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); +#endif } /** @@ -299,7 +310,7 @@ static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uin 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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[92]; + char buf[MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN]; _mav_put_uint64_t(buf, 0, cam_id); _mav_put_uint64_t(buf, 8, timestamp); _mav_put_uint64_t(buf, 16, valid_until); @@ -324,7 +335,11 @@ static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 90, cam_no); _mav_put_uint8_t(buf, 91, channels); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, 92, 224); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); +#endif #else mavlink_image_available_t packet; packet.cam_id = cam_id; @@ -351,7 +366,11 @@ static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint packet.cam_no = cam_no; packet.channels = channels; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, 92, 224); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); +#endif #endif } @@ -623,6 +642,6 @@ static inline void mavlink_msg_image_available_decode(const mavlink_message_t* m image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); image_available->channels = mavlink_msg_image_available_get_channels(msg); #else - memcpy(image_available, _MAV_PAYLOAD(msg), 92); + memcpy(image_available, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h index deb05769a1e36ece25625a7a7b6876a8c332a865..784cedf8b5e61d4ac47fae4c42da6a3e99cf76ee 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h @@ -10,6 +10,9 @@ typedef struct __mavlink_image_trigger_control_t #define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN 1 #define MAVLINK_MSG_ID_153_LEN 1 +#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC 95 +#define MAVLINK_MSG_ID_153_CRC 95 + #define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL { \ @@ -33,19 +36,23 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t enable) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[1]; + char buf[MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN]; _mav_put_uint8_t(buf, 0, enable); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); #else mavlink_image_trigger_control_t packet; packet.enable = enable; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 1, 95); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); +#endif } /** @@ -62,19 +69,23 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t syste uint8_t enable) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[1]; + char buf[MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN]; _mav_put_uint8_t(buf, 0, enable); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); #else mavlink_image_trigger_control_t packet; packet.enable = enable; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 1, 95); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); +#endif } /** @@ -101,15 +112,23 @@ static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_i static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[1]; + char buf[MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN]; _mav_put_uint8_t(buf, 0, enable); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, 1, 95); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); +#endif #else mavlink_image_trigger_control_t packet; packet.enable = enable; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, 1, 95); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); +#endif #endif } @@ -139,6 +158,6 @@ static inline void mavlink_msg_image_trigger_control_decode(const mavlink_messag #if MAVLINK_NEED_BYTE_SWAP image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg); #else - memcpy(image_trigger_control, _MAV_PAYLOAD(msg), 1); + memcpy(image_trigger_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h index 557d748e125500bde810e82dfa7f5dbfbb9e5b20..05b0d775fd56e586d290f087be3ac1e1bf79fb99 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h @@ -21,6 +21,9 @@ typedef struct __mavlink_image_triggered_t #define MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN 52 #define MAVLINK_MSG_ID_152_LEN 52 +#define MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC 86 +#define MAVLINK_MSG_ID_152_CRC 86 + #define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED { \ @@ -66,7 +69,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[52]; + char buf[MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN]; _mav_put_uint64_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 8, seq); _mav_put_float(buf, 12, roll); @@ -80,7 +83,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 _mav_put_float(buf, 44, ground_y); _mav_put_float(buf, 48, ground_z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); #else mavlink_image_triggered_t packet; packet.timestamp = timestamp; @@ -96,11 +99,15 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 packet.ground_y = ground_y; packet.ground_z = ground_z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; - return mavlink_finalize_message(msg, system_id, component_id, 52, 86); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); +#endif } /** @@ -128,7 +135,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, 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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[52]; + char buf[MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN]; _mav_put_uint64_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 8, seq); _mav_put_float(buf, 12, roll); @@ -142,7 +149,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, _mav_put_float(buf, 44, ground_y); _mav_put_float(buf, 48, ground_z); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); #else mavlink_image_triggered_t packet; packet.timestamp = timestamp; @@ -158,11 +165,15 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, packet.ground_y = ground_y; packet.ground_z = ground_z; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 52, 86); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); +#endif } /** @@ -200,7 +211,7 @@ static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uin 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) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[52]; + char buf[MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN]; _mav_put_uint64_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 8, seq); _mav_put_float(buf, 12, roll); @@ -214,7 +225,11 @@ static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint _mav_put_float(buf, 44, ground_y); _mav_put_float(buf, 48, ground_z); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, 52, 86); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); +#endif #else mavlink_image_triggered_t packet; packet.timestamp = timestamp; @@ -230,7 +245,11 @@ static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint packet.ground_y = ground_y; packet.ground_z = ground_z; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, 52, 86); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); +#endif #endif } @@ -381,6 +400,6 @@ static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* m image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg); image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg); #else - memcpy(image_triggered, _MAV_PAYLOAD(msg), 52); + memcpy(image_triggered, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h index 0c8cc6f18991c0c39cb3268a69642ca388b5d68a..817ec60a2043abc63f8d81e8f9f3b1241d5d9cd9 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h @@ -16,6 +16,9 @@ typedef struct __mavlink_marker_t #define MAVLINK_MSG_ID_MARKER_LEN 26 #define MAVLINK_MSG_ID_171_LEN 26 +#define MAVLINK_MSG_ID_MARKER_CRC 249 +#define MAVLINK_MSG_ID_171_CRC 249 + #define MAVLINK_MESSAGE_INFO_MARKER { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_MARKER_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon _mav_put_float(buf, 20, yaw); _mav_put_uint16_t(buf, 24, id); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MARKER_LEN); #else mavlink_marker_t packet; packet.x = x; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon packet.yaw = yaw; packet.id = id; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MARKER_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MARKER; - return mavlink_finalize_message(msg, system_id, component_id, 26, 249); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MARKER_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t c uint16_t id,float x,float y,float z,float roll,float pitch,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_MARKER_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t c _mav_put_float(buf, 20, yaw); _mav_put_uint16_t(buf, 24, id); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MARKER_LEN); #else mavlink_marker_t packet; packet.x = x; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t c packet.yaw = yaw; packet.id = id; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MARKER_LEN); #endif msg->msgid = MAVLINK_MSG_ID_MARKER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 249); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MARKER_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t comp static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[26]; + char buf[MAVLINK_MSG_ID_MARKER_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -164,7 +175,11 @@ static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, _mav_put_float(buf, 20, yaw); _mav_put_uint16_t(buf, 24, id); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, 26, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN); +#endif #else mavlink_marker_t packet; packet.x = x; @@ -175,7 +190,11 @@ static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, packet.yaw = yaw; packet.id = id; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, 26, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, MAVLINK_MSG_ID_MARKER_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavli marker->yaw = mavlink_msg_marker_get_yaw(msg); marker->id = mavlink_msg_marker_get_id(msg); #else - memcpy(marker, _MAV_PAYLOAD(msg), 26); + memcpy(marker, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MARKER_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h index 907246b207478ed5a8843aebb0b4de904b8152f9..7e29d7152584be0639f1dcac06f2885392751b42 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h @@ -13,6 +13,9 @@ typedef struct __mavlink_pattern_detected_t #define MAVLINK_MSG_ID_PATTERN_DETECTED_LEN 106 #define MAVLINK_MSG_ID_190_LEN 106 +#define MAVLINK_MSG_ID_PATTERN_DETECTED_CRC 90 +#define MAVLINK_MSG_ID_190_CRC 90 + #define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100 #define MAVLINK_MESSAGE_INFO_PATTERN_DETECTED { \ @@ -42,23 +45,27 @@ static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint uint8_t type, float confidence, const char *file, uint8_t detected) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[106]; + char buf[MAVLINK_MSG_ID_PATTERN_DETECTED_LEN]; _mav_put_float(buf, 0, confidence); _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 105, detected); _mav_put_char_array(buf, 5, file, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); #else mavlink_pattern_detected_t packet; packet.confidence = confidence; packet.type = type; packet.detected = detected; mav_array_memcpy(packet.file, file, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; - return mavlink_finalize_message(msg, system_id, component_id, 106, 90); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); +#endif } /** @@ -78,23 +85,27 @@ static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t type,float confidence,const char *file,uint8_t detected) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[106]; + char buf[MAVLINK_MSG_ID_PATTERN_DETECTED_LEN]; _mav_put_float(buf, 0, confidence); _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 105, detected); _mav_put_char_array(buf, 5, file, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); #else mavlink_pattern_detected_t packet; packet.confidence = confidence; packet.type = type; packet.detected = detected; mav_array_memcpy(packet.file, file, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 106, 90); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); +#endif } /** @@ -124,19 +135,27 @@ static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, ui static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const char *file, uint8_t detected) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[106]; + char buf[MAVLINK_MSG_ID_PATTERN_DETECTED_LEN]; _mav_put_float(buf, 0, confidence); _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 105, detected); _mav_put_char_array(buf, 5, file, 100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, 106, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); +#endif #else mavlink_pattern_detected_t packet; packet.confidence = confidence; packet.type = type; packet.detected = detected; mav_array_memcpy(packet.file, file, sizeof(char)*100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, 106, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); +#endif #endif } @@ -199,6 +218,6 @@ static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file); pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg); #else - memcpy(pattern_detected, _MAV_PAYLOAD(msg), 106); + memcpy(pattern_detected, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h index eec8d40691ca9d90915a6e3e972dd0ccf5ac429d..a6faebbb5ac1cc73914ba46157ffb09b151b39b6 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h @@ -17,6 +17,9 @@ typedef struct __mavlink_point_of_interest_t #define MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN 43 #define MAVLINK_MSG_ID_191_LEN 43 +#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC 95 +#define MAVLINK_MSG_ID_191_CRC 95 + #define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 26 #define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST { \ @@ -54,7 +57,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[43]; + char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin _mav_put_uint8_t(buf, 15, color); _mav_put_uint8_t(buf, 16, coordinate_system); _mav_put_char_array(buf, 17, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); #else mavlink_point_of_interest_t packet; packet.x = x; @@ -74,11 +77,15 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin packet.color = color; packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; - return mavlink_finalize_message(msg, system_id, component_id, 43, 95); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); +#endif } /** @@ -102,7 +109,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float x,float y,float z,const char *name) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[43]; + char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -111,7 +118,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id _mav_put_uint8_t(buf, 15, color); _mav_put_uint8_t(buf, 16, coordinate_system); _mav_put_char_array(buf, 17, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); #else mavlink_point_of_interest_t packet; packet.x = x; @@ -122,11 +129,15 @@ static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id packet.color = color; packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 43, 95); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); +#endif } /** @@ -160,7 +171,7 @@ static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, u static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[43]; + char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -169,7 +180,11 @@ static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, ui _mav_put_uint8_t(buf, 15, color); _mav_put_uint8_t(buf, 16, coordinate_system); _mav_put_char_array(buf, 17, name, 26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, 43, 95); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); +#endif #else mavlink_point_of_interest_t packet; packet.x = x; @@ -180,7 +195,11 @@ static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, ui packet.color = color; packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, 43, 95); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); +#endif #endif } @@ -287,6 +306,6 @@ static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg); mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name); #else - memcpy(point_of_interest, _MAV_PAYLOAD(msg), 43); + memcpy(point_of_interest, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h index f83630093ea1f6616addc000235c30146d738df7..8d02f9e5c45614b542b3d8a39b17063064ae791a 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h @@ -20,6 +20,9 @@ typedef struct __mavlink_point_of_interest_connection_t #define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN 55 #define MAVLINK_MSG_ID_192_LEN 55 +#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC 36 +#define MAVLINK_MSG_ID_192_CRC 36 + #define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 26 #define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION { \ @@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[55]; + char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN]; _mav_put_float(buf, 0, xp1); _mav_put_float(buf, 4, yp1); _mav_put_float(buf, 8, zp1); @@ -75,7 +78,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys _mav_put_uint8_t(buf, 27, color); _mav_put_uint8_t(buf, 28, coordinate_system); _mav_put_char_array(buf, 29, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); #else mavlink_point_of_interest_connection_t packet; packet.xp1 = xp1; @@ -89,11 +92,15 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys packet.color = color; packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; - return mavlink_finalize_message(msg, system_id, component_id, 55, 36); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); +#endif } /** @@ -120,7 +127,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_ uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float xp1,float yp1,float zp1,float xp2,float yp2,float zp2,const char *name) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[55]; + char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN]; _mav_put_float(buf, 0, xp1); _mav_put_float(buf, 4, yp1); _mav_put_float(buf, 8, zp1); @@ -132,7 +139,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_ _mav_put_uint8_t(buf, 27, color); _mav_put_uint8_t(buf, 28, coordinate_system); _mav_put_char_array(buf, 29, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); #else mavlink_point_of_interest_connection_t packet; packet.xp1 = xp1; @@ -146,11 +153,15 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_ packet.color = color; packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 55, 36); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); +#endif } /** @@ -187,7 +198,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t s static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[55]; + char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN]; _mav_put_float(buf, 0, xp1); _mav_put_float(buf, 4, yp1); _mav_put_float(buf, 8, zp1); @@ -199,7 +210,11 @@ static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel _mav_put_uint8_t(buf, 27, color); _mav_put_uint8_t(buf, 28, coordinate_system); _mav_put_char_array(buf, 29, name, 26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, 55, 36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); +#endif #else mavlink_point_of_interest_connection_t packet; packet.xp1 = xp1; @@ -213,7 +228,11 @@ static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel packet.color = color; packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, 55, 36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); +#endif #endif } @@ -353,6 +372,6 @@ static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg); mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name); #else - memcpy(point_of_interest_connection, _MAV_PAYLOAD(msg), 55); + memcpy(point_of_interest_connection, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h index 495fb884cf1346995e17455155d6b5e13961f768..6c86be3ab5688052f00809564b64fc0fc7e7fb8b 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h @@ -14,6 +14,9 @@ typedef struct __mavlink_position_control_setpoint_t #define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN 18 #define MAVLINK_MSG_ID_170_LEN 18 +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC 28 +#define MAVLINK_MSG_ID_170_CRC 28 + #define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT { \ @@ -45,14 +48,14 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system uint16_t id, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); _mav_put_uint16_t(buf, 16, id); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); #else mavlink_position_control_setpoint_t packet; packet.x = x; @@ -61,11 +64,15 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system packet.yaw = yaw; packet.id = id; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 18, 28); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); +#endif } /** @@ -86,14 +93,14 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t s uint16_t id,float x,float y,float z,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); _mav_put_uint16_t(buf, 16, id); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); #else mavlink_position_control_setpoint_t packet; packet.x = x; @@ -102,11 +109,15 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t s packet.yaw = yaw; packet.id = id; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 28); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); +#endif } /** @@ -137,14 +148,18 @@ static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t syst static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); _mav_put_uint16_t(buf, 16, id); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, 18, 28); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); +#endif #else mavlink_position_control_setpoint_t packet; packet.x = x; @@ -153,7 +168,11 @@ static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t packet.yaw = yaw; packet.id = id; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, 18, 28); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); +#endif #endif } @@ -227,6 +246,6 @@ static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_me position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); #else - memcpy(position_control_setpoint, _MAV_PAYLOAD(msg), 18); + memcpy(position_control_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h index 507e0f2f9bb49659758be951f8ba066b4c9c6826..0a0dbdb37891e685a30c8e683f888b700a87ab12 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h @@ -16,6 +16,9 @@ typedef struct __mavlink_raw_aux_t #define MAVLINK_MSG_ID_RAW_AUX_LEN 16 #define MAVLINK_MSG_ID_172_LEN 16 +#define MAVLINK_MSG_ID_RAW_AUX_CRC 182 +#define MAVLINK_MSG_ID_172_CRC 182 + #define MAVLINK_MESSAGE_INFO_RAW_AUX { \ @@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_RAW_AUX_LEN]; _mav_put_int32_t(buf, 0, baro); _mav_put_uint16_t(buf, 4, adc1); _mav_put_uint16_t(buf, 6, adc2); @@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo _mav_put_uint16_t(buf, 12, vbat); _mav_put_int16_t(buf, 14, temp); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_AUX_LEN); #else mavlink_raw_aux_t packet; packet.baro = baro; @@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo packet.vbat = vbat; packet.temp = temp; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_AUX_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RAW_AUX; - return mavlink_finalize_message(msg, system_id, component_id, 16, 182); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_AUX_LEN); +#endif } /** @@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t vbat,int16_t temp,int32_t baro) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_RAW_AUX_LEN]; _mav_put_int32_t(buf, 0, baro); _mav_put_uint16_t(buf, 4, adc1); _mav_put_uint16_t(buf, 6, adc2); @@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t _mav_put_uint16_t(buf, 12, vbat); _mav_put_int16_t(buf, 14, temp); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_AUX_LEN); #else mavlink_raw_aux_t packet; packet.baro = baro; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t packet.vbat = vbat; packet.temp = temp; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_AUX_LEN); #endif msg->msgid = MAVLINK_MSG_ID_RAW_AUX; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 182); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_AUX_LEN); +#endif } /** @@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[16]; + char buf[MAVLINK_MSG_ID_RAW_AUX_LEN]; _mav_put_int32_t(buf, 0, baro); _mav_put_uint16_t(buf, 4, adc1); _mav_put_uint16_t(buf, 6, adc2); @@ -164,7 +175,11 @@ static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc _mav_put_uint16_t(buf, 12, vbat); _mav_put_int16_t(buf, 14, temp); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, 16, 182); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN); +#endif #else mavlink_raw_aux_t packet; packet.baro = baro; @@ -175,7 +190,11 @@ static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc packet.vbat = vbat; packet.temp = temp; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, 16, 182); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, MAVLINK_MSG_ID_RAW_AUX_LEN); +#endif #endif } @@ -271,6 +290,6 @@ static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavl raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg); raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg); #else - memcpy(raw_aux, _MAV_PAYLOAD(msg), 16); + memcpy(raw_aux, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_AUX_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h index 698625b7e1f0fd5cda21ec7c40112143ae5da27e..7be6409119089fbc6d14d6e673f5ae42242ac3cb 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h @@ -15,6 +15,9 @@ typedef struct __mavlink_set_cam_shutter_t #define MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN 11 #define MAVLINK_MSG_ID_151_LEN 11 +#define MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC 108 +#define MAVLINK_MSG_ID_151_CRC 108 + #define MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8 uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[11]; + char buf[MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN]; _mav_put_float(buf, 0, gain); _mav_put_uint16_t(buf, 4, interval); _mav_put_uint16_t(buf, 6, exposure); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 9, cam_mode); _mav_put_uint8_t(buf, 10, trigger_pin); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); #else mavlink_set_cam_shutter_t packet; packet.gain = gain; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8 packet.cam_mode = cam_mode; packet.trigger_pin = trigger_pin; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; - return mavlink_finalize_message(msg, system_id, component_id, 11, 108); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t cam_no,uint8_t cam_mode,uint8_t trigger_pin,uint16_t interval,uint16_t exposure,float gain) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[11]; + char buf[MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN]; _mav_put_float(buf, 0, gain); _mav_put_uint16_t(buf, 4, interval); _mav_put_uint16_t(buf, 6, exposure); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 9, cam_mode); _mav_put_uint8_t(buf, 10, trigger_pin); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); #else mavlink_set_cam_shutter_t packet; packet.gain = gain; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, packet.cam_mode = cam_mode; packet.trigger_pin = trigger_pin; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11, 108); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uin static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[11]; + char buf[MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN]; _mav_put_float(buf, 0, gain); _mav_put_uint16_t(buf, 4, interval); _mav_put_uint16_t(buf, 6, exposure); @@ -154,7 +165,11 @@ static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint _mav_put_uint8_t(buf, 9, cam_mode); _mav_put_uint8_t(buf, 10, trigger_pin); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, 11, 108); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); +#endif #else mavlink_set_cam_shutter_t packet; packet.gain = gain; @@ -164,7 +179,11 @@ static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint packet.cam_mode = cam_mode; packet.trigger_pin = trigger_pin; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, 11, 108); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* m set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg); set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg); #else - memcpy(set_cam_shutter, _MAV_PAYLOAD(msg), 11); + memcpy(set_cam_shutter, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h index 27c08b7c9ce289430bcef88367a8ddbcf47d55b4..25bff659edd0d31c7e7f464f88242cd23e85871c 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h @@ -15,6 +15,9 @@ typedef struct __mavlink_set_position_control_offset_t #define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN 18 #define MAVLINK_MSG_ID_160_LEN 18 +#define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC 22 +#define MAVLINK_MSG_ID_160_CRC 22 + #define MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack(uint8_t syst uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack(uint8_t syst _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); #else mavlink_set_position_control_offset_t packet; packet.x = x; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack(uint8_t syst packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET; - return mavlink_finalize_message(msg, system_id, component_id, 18, 22); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack_chan(uint8_t uint8_t target_system,uint8_t target_component,float x,float y,float z,float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack_chan(uint8_t _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); #else mavlink_set_position_control_offset_t packet; packet.x = x; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack_chan(uint8_t packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 22); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_encode(uint8_t sy static inline void mavlink_msg_set_position_control_offset_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; + char buf[MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN]; _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); @@ -154,7 +165,11 @@ static inline void mavlink_msg_set_position_control_offset_send(mavlink_channel_ _mav_put_uint8_t(buf, 16, target_system); _mav_put_uint8_t(buf, 17, target_component); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, 18, 22); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); +#endif #else mavlink_set_position_control_offset_t packet; packet.x = x; @@ -164,7 +179,11 @@ static inline void mavlink_msg_set_position_control_offset_send(mavlink_channel_ packet.target_system = target_system; packet.target_component = target_component; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)&packet, 18, 22); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_set_position_control_offset_decode(const mavlink_ set_position_control_offset->target_system = mavlink_msg_set_position_control_offset_get_target_system(msg); set_position_control_offset->target_component = mavlink_msg_set_position_control_offset_get_target_component(msg); #else - memcpy(set_position_control_offset, _MAV_PAYLOAD(msg), 18); + memcpy(set_position_control_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h index 240f69e727680904c9d78035d7e43b8a460e016f..42678801869a730ad96bc990ae165f698fc68b52 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h @@ -13,6 +13,9 @@ typedef struct __mavlink_watchdog_command_t #define MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN 6 #define MAVLINK_MSG_ID_183_LEN 6 +#define MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC 162 +#define MAVLINK_MSG_ID_183_CRC 162 + #define MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND { \ @@ -42,13 +45,13 @@ static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN]; _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_id); _mav_put_uint8_t(buf, 4, target_system_id); _mav_put_uint8_t(buf, 5, command_id); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); #else mavlink_watchdog_command_t packet; packet.watchdog_id = watchdog_id; @@ -56,11 +59,15 @@ static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint packet.target_system_id = target_system_id; packet.command_id = command_id; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; - return mavlink_finalize_message(msg, system_id, component_id, 6, 162); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); +#endif } /** @@ -80,13 +87,13 @@ static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t target_system_id,uint16_t watchdog_id,uint16_t process_id,uint8_t command_id) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN]; _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_id); _mav_put_uint8_t(buf, 4, target_system_id); _mav_put_uint8_t(buf, 5, command_id); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); #else mavlink_watchdog_command_t packet; packet.watchdog_id = watchdog_id; @@ -94,11 +101,15 @@ static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, packet.target_system_id = target_system_id; packet.command_id = command_id; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 162); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); +#endif } /** @@ -128,13 +139,17 @@ static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, ui static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[6]; + char buf[MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN]; _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_id); _mav_put_uint8_t(buf, 4, target_system_id); _mav_put_uint8_t(buf, 5, command_id); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, 6, 162); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); +#endif #else mavlink_watchdog_command_t packet; packet.watchdog_id = watchdog_id; @@ -142,7 +157,11 @@ static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uin packet.target_system_id = target_system_id; packet.command_id = command_id; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, 6, 162); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); +#endif #endif } @@ -205,6 +224,6 @@ static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); #else - memcpy(watchdog_command, _MAV_PAYLOAD(msg), 6); + memcpy(watchdog_command, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h index f1fe5eb86a0649fdd7a6635ca7b86be64b551d32..49478999cecc0c6a5b8a460d5f05a3fdef4cbf76 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h @@ -11,6 +11,9 @@ typedef struct __mavlink_watchdog_heartbeat_t #define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN 4 #define MAVLINK_MSG_ID_180_LEN 4 +#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC 153 +#define MAVLINK_MSG_ID_180_CRC 153 + #define MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT { \ @@ -36,21 +39,25 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, ui uint16_t watchdog_id, uint16_t process_count) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN]; _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_count); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); #else mavlink_watchdog_heartbeat_t packet; packet.watchdog_id = watchdog_id; packet.process_count = process_count; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; - return mavlink_finalize_message(msg, system_id, component_id, 4, 153); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); +#endif } /** @@ -68,21 +75,25 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_i uint16_t watchdog_id,uint16_t process_count) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN]; _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_count); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); #else mavlink_watchdog_heartbeat_t packet; packet.watchdog_id = watchdog_id; packet.process_count = process_count; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 153); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); +#endif } /** @@ -110,17 +121,25 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN]; _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_count); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, 4, 153); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); +#endif #else mavlink_watchdog_heartbeat_t packet; packet.watchdog_id = watchdog_id; packet.process_count = process_count; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, 4, 153); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); +#endif #endif } @@ -161,6 +180,6 @@ static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg); watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg); #else - memcpy(watchdog_heartbeat, _MAV_PAYLOAD(msg), 4); + memcpy(watchdog_heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h index 7ba3ddf0378a4fa907f7affe28f3b9796f012cfa..d706ef85e1daf285bf7fddc8283e7d0f6be43d9a 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h @@ -14,6 +14,9 @@ typedef struct __mavlink_watchdog_process_info_t #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN 255 #define MAVLINK_MSG_ID_181_LEN 255 +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC 16 +#define MAVLINK_MSG_ID_181_CRC 16 + #define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100 #define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147 @@ -46,13 +49,13 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[255]; + char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN]; _mav_put_int32_t(buf, 0, timeout); _mav_put_uint16_t(buf, 4, watchdog_id); _mav_put_uint16_t(buf, 6, process_id); _mav_put_char_array(buf, 8, name, 100); _mav_put_char_array(buf, 108, arguments, 147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); #else mavlink_watchdog_process_info_t packet; packet.timeout = timeout; @@ -60,11 +63,15 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, packet.process_id = process_id; mav_array_memcpy(packet.name, name, sizeof(char)*100); mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; - return mavlink_finalize_message(msg, system_id, component_id, 255, 16); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); +#endif } /** @@ -85,13 +92,13 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t syste uint16_t watchdog_id,uint16_t process_id,const char *name,const char *arguments,int32_t timeout) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[255]; + char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN]; _mav_put_int32_t(buf, 0, timeout); _mav_put_uint16_t(buf, 4, watchdog_id); _mav_put_uint16_t(buf, 6, process_id); _mav_put_char_array(buf, 8, name, 100); _mav_put_char_array(buf, 108, arguments, 147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); #else mavlink_watchdog_process_info_t packet; packet.timeout = timeout; @@ -99,11 +106,15 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t syste packet.process_id = process_id; mav_array_memcpy(packet.name, name, sizeof(char)*100); mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255, 16); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); +#endif } /** @@ -134,13 +145,17 @@ static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_i static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[255]; + char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN]; _mav_put_int32_t(buf, 0, timeout); _mav_put_uint16_t(buf, 4, watchdog_id); _mav_put_uint16_t(buf, 6, process_id); _mav_put_char_array(buf, 8, name, 100); _mav_put_char_array(buf, 108, arguments, 147); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, 255, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); +#endif #else mavlink_watchdog_process_info_t packet; packet.timeout = timeout; @@ -148,7 +163,11 @@ static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan packet.process_id = process_id; mav_array_memcpy(packet.name, name, sizeof(char)*100); mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, 255, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); +#endif #endif } @@ -222,6 +241,6 @@ static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_messag mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name); mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments); #else - memcpy(watchdog_process_info, _MAV_PAYLOAD(msg), 255); + memcpy(watchdog_process_info, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h index 5795c63283e94129b9d85ce983b89eb6d801b88e..b1bbaaae7b181b05b0819d05bca2563092dd2ba9 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h @@ -15,6 +15,9 @@ typedef struct __mavlink_watchdog_process_status_t #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12 #define MAVLINK_MSG_ID_182_LEN 12 +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC 29 +#define MAVLINK_MSG_ID_182_CRC 29 + #define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS { \ @@ -48,7 +51,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN]; _mav_put_int32_t(buf, 0, pid); _mav_put_uint16_t(buf, 4, watchdog_id); _mav_put_uint16_t(buf, 6, process_id); @@ -56,7 +59,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i _mav_put_uint8_t(buf, 10, state); _mav_put_uint8_t(buf, 11, muted); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); #else mavlink_watchdog_process_status_t packet; packet.pid = pid; @@ -66,11 +69,15 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i packet.state = state; packet.muted = muted; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 12, 29); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); +#endif } /** @@ -92,7 +99,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t sys uint16_t watchdog_id,uint16_t process_id,uint8_t state,uint8_t muted,int32_t pid,uint16_t crashes) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN]; _mav_put_int32_t(buf, 0, pid); _mav_put_uint16_t(buf, 4, watchdog_id); _mav_put_uint16_t(buf, 6, process_id); @@ -100,7 +107,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t sys _mav_put_uint8_t(buf, 10, state); _mav_put_uint8_t(buf, 11, muted); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); #else mavlink_watchdog_process_status_t packet; packet.pid = pid; @@ -110,11 +117,15 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t sys packet.state = state; packet.muted = muted; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 29); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); +#endif } /** @@ -146,7 +157,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN]; _mav_put_int32_t(buf, 0, pid); _mav_put_uint16_t(buf, 4, watchdog_id); _mav_put_uint16_t(buf, 6, process_id); @@ -154,7 +165,11 @@ static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t ch _mav_put_uint8_t(buf, 10, state); _mav_put_uint8_t(buf, 11, muted); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, 12, 29); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); +#endif #else mavlink_watchdog_process_status_t packet; packet.pid = pid; @@ -164,7 +179,11 @@ static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t ch packet.state = state; packet.muted = muted; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, 12, 29); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); +#endif #endif } @@ -249,6 +268,6 @@ static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_mess watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg); watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg); #else - memcpy(watchdog_process_status, _MAV_PAYLOAD(msg), 12); + memcpy(watchdog_process_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h index 574b92d7a8e68d0d52224d5fd7954b5481330db9..39269f465f99eadbf75cf4f18fd57a2074088c28 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 88, 44, 9, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 5, 212, 185, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" diff --git a/libs/mavlink/include/mavlink/v1.0/pixhawk/version.h b/libs/mavlink/include/mavlink/v1.0/pixhawk/version.h index 2ece894096c1cbb5d7d8eef43ee294298578c03f..8188957c060667d5c1114afcc93f4c02b82d04ca 100644 --- a/libs/mavlink/include/mavlink/v1.0/pixhawk/version.h +++ b/libs/mavlink/include/mavlink/v1.0/pixhawk/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Wed Jan 9 16:18:21 2013" +#define MAVLINK_BUILD_DATE "Fri Jun 7 22:42:06 2013" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/libs/mavlink/include/mavlink/v1.0/protocol.h b/libs/mavlink/include/mavlink/v1.0/protocol.h index 64dc222291d42edbc2fa5b66b595a3c1224212b4..ddacae59c4cbefe6381440942e161ff532a37133 100644 --- a/libs/mavlink/include/mavlink/v1.0/protocol.h +++ b/libs/mavlink/include/mavlink/v1.0/protocol.h @@ -60,7 +60,9 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui uint8_t chan, uint8_t length); MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint8_t length); +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); +#endif #endif // MAVLINK_CRC_EXTRA MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h index 74b55af304ab0ef76c9c9a9ae3a6a72ff16ad75b..5cdd584561f87a0f77e3e012a1b603164ec8cda4 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h @@ -15,6 +15,9 @@ typedef struct __mavlink_cmd_airspeed_ack_t #define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN 5 #define MAVLINK_MSG_ID_194_LEN 5 +#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC 243 +#define MAVLINK_MSG_ID_194_CRC 243 + #define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK { \ @@ -44,21 +47,25 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint float spCmd, uint8_t ack) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[5]; + char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN]; _mav_put_float(buf, 0, spCmd); _mav_put_uint8_t(buf, 4, ack); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); #else mavlink_cmd_airspeed_ack_t packet; packet.spCmd = spCmd; packet.ack = ack; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK; - return mavlink_finalize_message(msg, system_id, component_id, 5, 243); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); +#endif } /** @@ -80,21 +87,25 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, float spCmd,uint8_t ack) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[5]; + char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN]; _mav_put_float(buf, 0, spCmd); _mav_put_uint8_t(buf, 4, ack); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); #else mavlink_cmd_airspeed_ack_t packet; packet.spCmd = spCmd; packet.ack = ack; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 243); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); +#endif } /** @@ -126,17 +137,25 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, ui static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[5]; + char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN]; _mav_put_float(buf, 0, spCmd); _mav_put_uint8_t(buf, 4, ack); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, 5, 243); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); +#endif #else mavlink_cmd_airspeed_ack_t packet; packet.spCmd = spCmd; packet.ack = ack; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, 5, 243); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); +#endif #endif } @@ -181,6 +200,6 @@ static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg); cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg); #else - memcpy(cmd_airspeed_ack, _MAV_PAYLOAD(msg), 5); + memcpy(cmd_airspeed_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h index 2ac1b4eab09bc942cd0e417ac0d81b351d31728c..2a4894fe72a5b88ba421ee49a918778c9499ea72 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h @@ -15,6 +15,9 @@ typedef struct __mavlink_cmd_airspeed_chng_t #define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN 5 #define MAVLINK_MSG_ID_192_LEN 5 +#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC 209 +#define MAVLINK_MSG_ID_192_CRC 209 + #define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG { \ @@ -44,21 +47,25 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uin uint8_t target, float spCmd) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[5]; + char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN]; _mav_put_float(buf, 0, spCmd); _mav_put_uint8_t(buf, 4, target); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); #else mavlink_cmd_airspeed_chng_t packet; packet.spCmd = spCmd; packet.target = target; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG; - return mavlink_finalize_message(msg, system_id, component_id, 5, 209); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); +#endif } /** @@ -80,21 +87,25 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id uint8_t target,float spCmd) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[5]; + char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN]; _mav_put_float(buf, 0, spCmd); _mav_put_uint8_t(buf, 4, target); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); #else mavlink_cmd_airspeed_chng_t packet; packet.spCmd = spCmd; packet.target = target; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); #endif msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 209); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); +#endif } /** @@ -126,17 +137,25 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, u static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[5]; + char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN]; _mav_put_float(buf, 0, spCmd); _mav_put_uint8_t(buf, 4, target); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, 5, 209); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); +#endif #else mavlink_cmd_airspeed_chng_t packet; packet.spCmd = spCmd; packet.target = target; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, 5, 209); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); +#endif #endif } @@ -181,6 +200,6 @@ static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg); cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg); #else - memcpy(cmd_airspeed_chng, _MAV_PAYLOAD(msg), 5); + memcpy(cmd_airspeed_chng, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h index 32f46aadc2e2daf2c58bf0d7c4ae0a9b6d0ab976..d600e917495852473f2fb197e1493af1dfd3d923 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h @@ -12,6 +12,9 @@ typedef struct __mavlink_filt_rot_vel_t #define MAVLINK_MSG_ID_FILT_ROT_VEL_LEN 12 #define MAVLINK_MSG_ID_184_LEN 12 +#define MAVLINK_MSG_ID_FILT_ROT_VEL_CRC 79 +#define MAVLINK_MSG_ID_184_CRC 79 + #define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3 #define MAVLINK_MESSAGE_INFO_FILT_ROT_VEL { \ @@ -37,19 +40,23 @@ static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t const float *rotVel) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_FILT_ROT_VEL_LEN]; _mav_put_float_array(buf, 0, rotVel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); #else mavlink_filt_rot_vel_t packet; mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL; - return mavlink_finalize_message(msg, system_id, component_id, 12, 79); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); +#endif } /** @@ -68,19 +75,23 @@ static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uin const float *rotVel) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_FILT_ROT_VEL_LEN]; _mav_put_float_array(buf, 0, rotVel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); #else mavlink_filt_rot_vel_t packet; mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); #endif msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 79); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); +#endif } /** @@ -109,15 +120,23 @@ static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float *rotVel) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_FILT_ROT_VEL_LEN]; _mav_put_float_array(buf, 0, rotVel, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, 12, 79); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); +#endif #else mavlink_filt_rot_vel_t packet; mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, 12, 79); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); +#endif #endif } @@ -149,6 +168,6 @@ static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, #if MAVLINK_NEED_BYTE_SWAP mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel); #else - memcpy(filt_rot_vel, _MAV_PAYLOAD(msg), 12); + memcpy(filt_rot_vel, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h index 41a66adef7d24fe6f4de6df7b476b460cf5efd7c..cb1c86f436e9d5ba000383b6f266a8f7e4e9a82d 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h @@ -15,6 +15,9 @@ typedef struct __mavlink_llc_out_t #define MAVLINK_MSG_ID_LLC_OUT_LEN 12 #define MAVLINK_MSG_ID_186_LEN 12 +#define MAVLINK_MSG_ID_LLC_OUT_CRC 5 +#define MAVLINK_MSG_ID_186_CRC 5 + #define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4 #define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2 @@ -45,21 +48,25 @@ static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t compo const int16_t *servoOut, const int16_t *MotorOut) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_LLC_OUT_LEN]; _mav_put_int16_t_array(buf, 0, servoOut, 4); _mav_put_int16_t_array(buf, 8, MotorOut, 2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LLC_OUT_LEN); #else mavlink_llc_out_t packet; mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LLC_OUT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LLC_OUT; - return mavlink_finalize_message(msg, system_id, component_id, 12, 5); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LLC_OUT_LEN); +#endif } /** @@ -81,21 +88,25 @@ static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t const int16_t *servoOut,const int16_t *MotorOut) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_LLC_OUT_LEN]; _mav_put_int16_t_array(buf, 0, servoOut, 4); _mav_put_int16_t_array(buf, 8, MotorOut, 2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LLC_OUT_LEN); #else mavlink_llc_out_t packet; mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LLC_OUT_LEN); #endif msg->msgid = MAVLINK_MSG_ID_LLC_OUT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 5); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LLC_OUT_LEN); +#endif } /** @@ -127,17 +138,25 @@ static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_t *servoOut, const int16_t *MotorOut) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_LLC_OUT_LEN]; _mav_put_int16_t_array(buf, 0, servoOut, 4); _mav_put_int16_t_array(buf, 8, MotorOut, 2); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, 12, 5); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN); +#endif #else mavlink_llc_out_t packet; mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, 12, 5); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, MAVLINK_MSG_ID_LLC_OUT_LEN); +#endif #endif } @@ -182,6 +201,6 @@ static inline void mavlink_msg_llc_out_decode(const mavlink_message_t* msg, mavl mavlink_msg_llc_out_get_servoOut(msg, llc_out->servoOut); mavlink_msg_llc_out_get_MotorOut(msg, llc_out->MotorOut); #else - memcpy(llc_out, _MAV_PAYLOAD(msg), 12); + memcpy(llc_out, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LLC_OUT_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h index 3e08b58426c91b95e98a26ecb2957db9193792f4..b6bd0d9e52ac0a55a9c748b65175df7f380e6aef 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h @@ -12,6 +12,9 @@ typedef struct __mavlink_obs_air_temp_t #define MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN 4 #define MAVLINK_MSG_ID_183_LEN 4 +#define MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC 248 +#define MAVLINK_MSG_ID_183_CRC 248 + #define MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP { \ @@ -37,19 +40,23 @@ static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t float airT) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN]; _mav_put_float(buf, 0, airT); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); #else mavlink_obs_air_temp_t packet; packet.airT = airT; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP; - return mavlink_finalize_message(msg, system_id, component_id, 4, 248); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); +#endif } /** @@ -68,19 +75,23 @@ static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uin float airT) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN]; _mav_put_float(buf, 0, airT); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); #else mavlink_obs_air_temp_t packet; packet.airT = airT; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 248); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); +#endif } /** @@ -109,15 +120,23 @@ static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float airT) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN]; _mav_put_float(buf, 0, airT); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, 4, 248); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); +#endif #else mavlink_obs_air_temp_t packet; packet.airT = airT; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, 4, 248); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); +#endif #endif } @@ -149,6 +168,6 @@ static inline void mavlink_msg_obs_air_temp_decode(const mavlink_message_t* msg, #if MAVLINK_NEED_BYTE_SWAP obs_air_temp->airT = mavlink_msg_obs_air_temp_get_airT(msg); #else - memcpy(obs_air_temp, _MAV_PAYLOAD(msg), 4); + memcpy(obs_air_temp, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h index 2f7c6f9e9ea23d2ef9419005b3a6da0ce2920e48..87a65cfa0624a40ffc41996caa626f484d53ca91 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h @@ -18,6 +18,9 @@ typedef struct __mavlink_obs_air_velocity_t #define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN 12 #define MAVLINK_MSG_ID_178_LEN 12 +#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC 32 +#define MAVLINK_MSG_ID_178_CRC 32 + #define MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY { \ @@ -51,23 +54,27 @@ static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint float magnitude, float aoa, float slip) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN]; _mav_put_float(buf, 0, magnitude); _mav_put_float(buf, 4, aoa); _mav_put_float(buf, 8, slip); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); #else mavlink_obs_air_velocity_t packet; packet.magnitude = magnitude; packet.aoa = aoa; packet.slip = slip; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY; - return mavlink_finalize_message(msg, system_id, component_id, 12, 32); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); +#endif } /** @@ -92,23 +99,27 @@ static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, float magnitude,float aoa,float slip) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN]; _mav_put_float(buf, 0, magnitude); _mav_put_float(buf, 4, aoa); _mav_put_float(buf, 8, slip); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); #else mavlink_obs_air_velocity_t packet; packet.magnitude = magnitude; packet.aoa = aoa; packet.slip = slip; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 32); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); +#endif } /** @@ -143,19 +154,27 @@ static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, ui static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, float magnitude, float aoa, float slip) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN]; _mav_put_float(buf, 0, magnitude); _mav_put_float(buf, 4, aoa); _mav_put_float(buf, 8, slip); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, 12, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); +#endif #else mavlink_obs_air_velocity_t packet; packet.magnitude = magnitude; packet.aoa = aoa; packet.slip = slip; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, 12, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); +#endif #endif } @@ -213,6 +232,6 @@ static inline void mavlink_msg_obs_air_velocity_decode(const mavlink_message_t* obs_air_velocity->aoa = mavlink_msg_obs_air_velocity_get_aoa(msg); obs_air_velocity->slip = mavlink_msg_obs_air_velocity_get_slip(msg); #else - memcpy(obs_air_velocity, _MAV_PAYLOAD(msg), 12); + memcpy(obs_air_velocity, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h index 3247392f63c4b075bf8b0bc36815de9ae0e2f27d..602eafc80b0f5d94920076d13f734570f7633a11 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h @@ -12,6 +12,9 @@ typedef struct __mavlink_obs_attitude_t #define MAVLINK_MSG_ID_OBS_ATTITUDE_LEN 32 #define MAVLINK_MSG_ID_174_LEN 32 +#define MAVLINK_MSG_ID_OBS_ATTITUDE_CRC 146 +#define MAVLINK_MSG_ID_174_CRC 146 + #define MAVLINK_MSG_OBS_ATTITUDE_FIELD_QUAT_LEN 4 #define MAVLINK_MESSAGE_INFO_OBS_ATTITUDE { \ @@ -37,19 +40,23 @@ static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t const double *quat) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_OBS_ATTITUDE_LEN]; _mav_put_double_array(buf, 0, quat, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); #else mavlink_obs_attitude_t packet; mav_array_memcpy(packet.quat, quat, sizeof(double)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, 32, 146); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); +#endif } /** @@ -68,19 +75,23 @@ static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uin const double *quat) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_OBS_ATTITUDE_LEN]; _mav_put_double_array(buf, 0, quat, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); #else mavlink_obs_attitude_t packet; mav_array_memcpy(packet.quat, quat, sizeof(double)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 146); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); +#endif } /** @@ -109,15 +120,23 @@ static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const double *quat) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[32]; + char buf[MAVLINK_MSG_ID_OBS_ATTITUDE_LEN]; _mav_put_double_array(buf, 0, quat, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, 32, 146); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); +#endif #else mavlink_obs_attitude_t packet; mav_array_memcpy(packet.quat, quat, sizeof(double)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, 32, 146); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); +#endif #endif } @@ -149,6 +168,6 @@ static inline void mavlink_msg_obs_attitude_decode(const mavlink_message_t* msg, #if MAVLINK_NEED_BYTE_SWAP mavlink_msg_obs_attitude_get_quat(msg, obs_attitude->quat); #else - memcpy(obs_attitude, _MAV_PAYLOAD(msg), 32); + memcpy(obs_attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h index 2a0d49f3435ea93dd178142deed0cf15ec1898d3..3ab855ba817c46ca4872094b0baff24058dd6c92 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h @@ -15,6 +15,9 @@ typedef struct __mavlink_obs_bias_t #define MAVLINK_MSG_ID_OBS_BIAS_LEN 24 #define MAVLINK_MSG_ID_180_LEN 24 +#define MAVLINK_MSG_ID_OBS_BIAS_CRC 159 +#define MAVLINK_MSG_ID_180_CRC 159 + #define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3 #define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3 @@ -45,21 +48,25 @@ static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t comp const float *accBias, const float *gyroBias) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_OBS_BIAS_LEN]; _mav_put_float_array(buf, 0, accBias, 3); _mav_put_float_array(buf, 12, gyroBias, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); #else mavlink_obs_bias_t packet; mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_BIAS; - return mavlink_finalize_message(msg, system_id, component_id, 24, 159); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_BIAS_LEN); +#endif } /** @@ -81,21 +88,25 @@ static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t const float *accBias,const float *gyroBias) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_OBS_BIAS_LEN]; _mav_put_float_array(buf, 0, accBias, 3); _mav_put_float_array(buf, 12, gyroBias, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); #else mavlink_obs_bias_t packet; mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_BIAS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 159); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_BIAS_LEN); +#endif } /** @@ -127,17 +138,25 @@ static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float *accBias, const float *gyroBias) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[24]; + char buf[MAVLINK_MSG_ID_OBS_BIAS_LEN]; _mav_put_float_array(buf, 0, accBias, 3); _mav_put_float_array(buf, 12, gyroBias, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, 24, 159); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); +#endif #else mavlink_obs_bias_t packet; mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, 24, 159); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); +#endif #endif } @@ -182,6 +201,6 @@ static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mav mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias); mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias); #else - memcpy(obs_bias, _MAV_PAYLOAD(msg), 24); + memcpy(obs_bias, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_BIAS_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h index 0d89bcdb731f9a934177e99be6775b74f6ce63db..ec494d51a2dff9fd81a2848c99dcac0e83060775 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h @@ -18,6 +18,9 @@ typedef struct __mavlink_obs_position_t #define MAVLINK_MSG_ID_OBS_POSITION_LEN 12 #define MAVLINK_MSG_ID_170_LEN 12 +#define MAVLINK_MSG_ID_OBS_POSITION_CRC 15 +#define MAVLINK_MSG_ID_170_CRC 15 + #define MAVLINK_MESSAGE_INFO_OBS_POSITION { \ @@ -51,23 +54,27 @@ static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t int32_t lon, int32_t lat, int32_t alt) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_POSITION_LEN]; _mav_put_int32_t(buf, 0, lon); _mav_put_int32_t(buf, 4, lat); _mav_put_int32_t(buf, 8, alt); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); #else mavlink_obs_position_t packet; packet.lon = lon; packet.lat = lat; packet.alt = alt; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, 12, 15); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_POSITION_LEN); +#endif } /** @@ -92,23 +99,27 @@ static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uin int32_t lon,int32_t lat,int32_t alt) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_POSITION_LEN]; _mav_put_int32_t(buf, 0, lon); _mav_put_int32_t(buf, 4, lat); _mav_put_int32_t(buf, 8, alt); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); #else mavlink_obs_position_t packet; packet.lon = lon; packet.lat = lat; packet.alt = alt; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 15); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_POSITION_LEN); +#endif } /** @@ -143,19 +154,27 @@ static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_POSITION_LEN]; _mav_put_int32_t(buf, 0, lon); _mav_put_int32_t(buf, 4, lat); _mav_put_int32_t(buf, 8, alt); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, 12, 15); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); +#endif #else mavlink_obs_position_t packet; packet.lon = lon; packet.lat = lat; packet.alt = alt; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, 12, 15); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); +#endif #endif } @@ -213,6 +232,6 @@ static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, obs_position->lat = mavlink_msg_obs_position_get_lat(msg); obs_position->alt = mavlink_msg_obs_position_get_alt(msg); #else - memcpy(obs_position, _MAV_PAYLOAD(msg), 12); + memcpy(obs_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_POSITION_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h index 1f32eff405b678aae86bb4708cfd88d8c8b098c2..e42b0261fa91d3af2387e30c8fb95fdc787e2169 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h @@ -12,6 +12,9 @@ typedef struct __mavlink_obs_qff_t #define MAVLINK_MSG_ID_OBS_QFF_LEN 4 #define MAVLINK_MSG_ID_182_LEN 4 +#define MAVLINK_MSG_ID_OBS_QFF_CRC 24 +#define MAVLINK_MSG_ID_182_CRC 24 + #define MAVLINK_MESSAGE_INFO_OBS_QFF { \ @@ -37,19 +40,23 @@ static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t compo float qff) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_OBS_QFF_LEN]; _mav_put_float(buf, 0, qff); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_QFF_LEN); #else mavlink_obs_qff_t packet; packet.qff = qff; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_QFF_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_QFF; - return mavlink_finalize_message(msg, system_id, component_id, 4, 24); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_QFF_LEN); +#endif } /** @@ -68,19 +75,23 @@ static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t float qff) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_OBS_QFF_LEN]; _mav_put_float(buf, 0, qff); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_QFF_LEN); #else mavlink_obs_qff_t packet; packet.qff = qff; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_QFF_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_QFF; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 24); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_QFF_LEN); +#endif } /** @@ -109,15 +120,23 @@ static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_OBS_QFF_LEN]; _mav_put_float(buf, 0, qff); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, 4, 24); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN); +#endif #else mavlink_obs_qff_t packet; packet.qff = qff; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, 4, 24); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, MAVLINK_MSG_ID_OBS_QFF_LEN); +#endif #endif } @@ -149,6 +168,6 @@ static inline void mavlink_msg_obs_qff_decode(const mavlink_message_t* msg, mavl #if MAVLINK_NEED_BYTE_SWAP obs_qff->qff = mavlink_msg_obs_qff_get_qff(msg); #else - memcpy(obs_qff, _MAV_PAYLOAD(msg), 4); + memcpy(obs_qff, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_QFF_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h index d0cc15e8b4e37fe7a8d37f9dc9e0a30b715663ab..2fa6e9111f50c00e0cf0c3ddb454df63deb6b3fc 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h @@ -12,6 +12,9 @@ typedef struct __mavlink_obs_velocity_t #define MAVLINK_MSG_ID_OBS_VELOCITY_LEN 12 #define MAVLINK_MSG_ID_172_LEN 12 +#define MAVLINK_MSG_ID_OBS_VELOCITY_CRC 108 +#define MAVLINK_MSG_ID_172_CRC 108 + #define MAVLINK_MSG_OBS_VELOCITY_FIELD_VEL_LEN 3 #define MAVLINK_MESSAGE_INFO_OBS_VELOCITY { \ @@ -37,19 +40,23 @@ static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t const float *vel) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_VELOCITY_LEN]; _mav_put_float_array(buf, 0, vel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); #else mavlink_obs_velocity_t packet; mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY; - return mavlink_finalize_message(msg, system_id, component_id, 12, 108); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); +#endif } /** @@ -68,19 +75,23 @@ static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uin const float *vel) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_VELOCITY_LEN]; _mav_put_float_array(buf, 0, vel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); #else mavlink_obs_velocity_t packet; mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 108); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); +#endif } /** @@ -109,15 +120,23 @@ static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_ static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const float *vel) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_VELOCITY_LEN]; _mav_put_float_array(buf, 0, vel, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, 12, 108); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); +#endif #else mavlink_obs_velocity_t packet; mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, 12, 108); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); +#endif #endif } @@ -149,6 +168,6 @@ static inline void mavlink_msg_obs_velocity_decode(const mavlink_message_t* msg, #if MAVLINK_NEED_BYTE_SWAP mavlink_msg_obs_velocity_get_vel(msg, obs_velocity->vel); #else - memcpy(obs_velocity, _MAV_PAYLOAD(msg), 12); + memcpy(obs_velocity, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_VELOCITY_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h index d08d41ae9a51b5990047b9c1bf29dafdd7a6f57d..bc9f6e4eff8074d16e349dee1b83210f0974ec02 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h @@ -12,6 +12,9 @@ typedef struct __mavlink_obs_wind_t #define MAVLINK_MSG_ID_OBS_WIND_LEN 12 #define MAVLINK_MSG_ID_176_LEN 12 +#define MAVLINK_MSG_ID_OBS_WIND_CRC 16 +#define MAVLINK_MSG_ID_176_CRC 16 + #define MAVLINK_MSG_OBS_WIND_FIELD_WIND_LEN 3 #define MAVLINK_MESSAGE_INFO_OBS_WIND { \ @@ -37,19 +40,23 @@ static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t comp const float *wind) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_WIND_LEN]; _mav_put_float_array(buf, 0, wind, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_WIND_LEN); #else mavlink_obs_wind_t packet; mav_array_memcpy(packet.wind, wind, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_WIND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_WIND; - return mavlink_finalize_message(msg, system_id, component_id, 12, 16); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_WIND_LEN); +#endif } /** @@ -68,19 +75,23 @@ static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t const float *wind) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_WIND_LEN]; _mav_put_float_array(buf, 0, wind, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_WIND_LEN); #else mavlink_obs_wind_t packet; mav_array_memcpy(packet.wind, wind, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_WIND_LEN); #endif msg->msgid = MAVLINK_MSG_ID_OBS_WIND; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 16); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_WIND_LEN); +#endif } /** @@ -109,15 +120,23 @@ static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float *wind) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[12]; + char buf[MAVLINK_MSG_ID_OBS_WIND_LEN]; _mav_put_float_array(buf, 0, wind, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, 12, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN); +#endif #else mavlink_obs_wind_t packet; mav_array_memcpy(packet.wind, wind, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, 12, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, MAVLINK_MSG_ID_OBS_WIND_LEN); +#endif #endif } @@ -149,6 +168,6 @@ static inline void mavlink_msg_obs_wind_decode(const mavlink_message_t* msg, mav #if MAVLINK_NEED_BYTE_SWAP mavlink_msg_obs_wind_get_wind(msg, obs_wind->wind); #else - memcpy(obs_wind, _MAV_PAYLOAD(msg), 12); + memcpy(obs_wind, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_WIND_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h index 5b7a4b2d65e2b138b83c5a998e448345bea9b38f..0799af07f833a37afb69ad1785ac578765ab9e68 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h @@ -18,6 +18,9 @@ typedef struct __mavlink_pm_elec_t #define MAVLINK_MSG_ID_PM_ELEC_LEN 20 #define MAVLINK_MSG_ID_188_LEN 20 +#define MAVLINK_MSG_ID_PM_ELEC_CRC 170 +#define MAVLINK_MSG_ID_188_CRC 170 + #define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3 #define MAVLINK_MESSAGE_INFO_PM_ELEC { \ @@ -51,21 +54,25 @@ static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t compo float PwCons, float BatStat, const float *PwGen) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_PM_ELEC_LEN]; _mav_put_float(buf, 0, PwCons); _mav_put_float(buf, 4, BatStat); _mav_put_float_array(buf, 8, PwGen, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PM_ELEC_LEN); #else mavlink_pm_elec_t packet; packet.PwCons = PwCons; packet.BatStat = BatStat; mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PM_ELEC_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PM_ELEC; - return mavlink_finalize_message(msg, system_id, component_id, 20, 170); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PM_ELEC_LEN); +#endif } /** @@ -90,21 +97,25 @@ static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t float PwCons,float BatStat,const float *PwGen) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_PM_ELEC_LEN]; _mav_put_float(buf, 0, PwCons); _mav_put_float(buf, 4, BatStat); _mav_put_float_array(buf, 8, PwGen, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PM_ELEC_LEN); #else mavlink_pm_elec_t packet; packet.PwCons = PwCons; packet.BatStat = BatStat; mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PM_ELEC_LEN); #endif msg->msgid = MAVLINK_MSG_ID_PM_ELEC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 170); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PM_ELEC_LEN); +#endif } /** @@ -139,17 +150,25 @@ static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t com static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; + char buf[MAVLINK_MSG_ID_PM_ELEC_LEN]; _mav_put_float(buf, 0, PwCons); _mav_put_float(buf, 4, BatStat); _mav_put_float_array(buf, 8, PwGen, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, 20, 170); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN); +#endif #else mavlink_pm_elec_t packet; packet.PwCons = PwCons; packet.BatStat = BatStat; mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, 20, 170); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, MAVLINK_MSG_ID_PM_ELEC_LEN); +#endif #endif } @@ -207,6 +226,6 @@ static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavl pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg); mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen); #else - memcpy(pm_elec, _MAV_PAYLOAD(msg), 20); + memcpy(pm_elec, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PM_ELEC_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h index ab5d8f8a8cddf842038d81493254b867b6bf7015..e5e483a73afd4dec1810a677cb75d811dfaaac7e 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h @@ -21,6 +21,9 @@ typedef struct __mavlink_sys_stat_t #define MAVLINK_MSG_ID_SYS_Stat_LEN 4 #define MAVLINK_MSG_ID_190_LEN 4 +#define MAVLINK_MSG_ID_SYS_Stat_CRC 157 +#define MAVLINK_MSG_ID_190_CRC 157 + #define MAVLINK_MESSAGE_INFO_SYS_Stat { \ @@ -58,13 +61,13 @@ static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t comp uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_SYS_Stat_LEN]; _mav_put_uint8_t(buf, 0, gps); _mav_put_uint8_t(buf, 1, act); _mav_put_uint8_t(buf, 2, mod); _mav_put_uint8_t(buf, 3, commRssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_Stat_LEN); #else mavlink_sys_stat_t packet; packet.gps = gps; @@ -72,11 +75,15 @@ static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t comp packet.mod = mod; packet.commRssi = commRssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_Stat_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SYS_Stat; - return mavlink_finalize_message(msg, system_id, component_id, 4, 157); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_Stat_LEN); +#endif } /** @@ -104,13 +111,13 @@ static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t uint8_t gps,uint8_t act,uint8_t mod,uint8_t commRssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_SYS_Stat_LEN]; _mav_put_uint8_t(buf, 0, gps); _mav_put_uint8_t(buf, 1, act); _mav_put_uint8_t(buf, 2, mod); _mav_put_uint8_t(buf, 3, commRssi); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_Stat_LEN); #else mavlink_sys_stat_t packet; packet.gps = gps; @@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t packet.mod = mod; packet.commRssi = commRssi; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_Stat_LEN); #endif msg->msgid = MAVLINK_MSG_ID_SYS_Stat; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 157); +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_Stat_LEN); +#endif } /** @@ -160,13 +171,17 @@ static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t co static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[4]; + char buf[MAVLINK_MSG_ID_SYS_Stat_LEN]; _mav_put_uint8_t(buf, 0, gps); _mav_put_uint8_t(buf, 1, act); _mav_put_uint8_t(buf, 2, mod); _mav_put_uint8_t(buf, 3, commRssi); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, 4, 157); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN); +#endif #else mavlink_sys_stat_t packet; packet.gps = gps; @@ -174,7 +189,11 @@ static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps packet.mod = mod; packet.commRssi = commRssi; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, 4, 157); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, MAVLINK_MSG_ID_SYS_Stat_LEN); +#endif #endif } @@ -245,6 +264,6 @@ static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mav sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg); sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg); #else - memcpy(sys_stat, _MAV_PAYLOAD(msg), 4); + memcpy(sys_stat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYS_Stat_LEN); #endif } diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h index 84b29698169b752e03665d5f589b1c549a2583c4..a8eb32afd18cbdcf06067c9856da2adaa9cb4ba1 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 0, 0, 0, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 88, 44, 9, 254, 249, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 5, 212, 185, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" diff --git a/libs/mavlink/include/mavlink/v1.0/sensesoar/version.h b/libs/mavlink/include/mavlink/v1.0/sensesoar/version.h index 18eb38f0043fef1f0efbe39004ebe44471d6d065..47a527dd0ee7e4ae7afdf73ad569e8b79337df4a 100644 --- a/libs/mavlink/include/mavlink/v1.0/sensesoar/version.h +++ b/libs/mavlink/include/mavlink/v1.0/sensesoar/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Wed Jan 9 16:19:38 2013" +#define MAVLINK_BUILD_DATE "Fri Jun 7 22:42:18 2013" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254 diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 485dbc20d37d502cc3a7fab28568b7ced379fff5..8689eb6c6fc1c4546b29d68b4c3aba86f6dbe11c 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -61,14 +61,14 @@ win32 { QMAKE_MOC = "$$(QTDIR)/bin/moc.exe" QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe" QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe" - - # Build QAX for GoogleEarth API access - !exists( $(QTDIR)/src/activeqt/Makefile ) { - message( Making QAx (ONE TIME) ) - system( cd $$(QTDIR)\\src\\activeqt && $$(QTDIR)\\bin\\qmake.exe ) - system( cd $$(QTDIR)\\src\\activeqt\\container && $$(QTDIR)\\bin\\qmake.exe ) - system( cd $$(QTDIR)\\src\\activeqt\\control && $$(QTDIR)\\bin\\qmake.exe ) - } + + # Build QAX for GoogleEarth API access + !exists( $(QTDIR)/src/activeqt/Makefile ) { + message( Making QAx (ONE TIME) ) + system( cd $$(QTDIR)\\src\\activeqt && $$(QTDIR)\\bin\\qmake.exe ) + system( cd $$(QTDIR)\\src\\activeqt\\container && $$(QTDIR)\\bin\\qmake.exe ) + system( cd $$(QTDIR)\\src\\activeqt\\control && $$(QTDIR)\\bin\\qmake.exe ) + } } @@ -100,14 +100,14 @@ INCLUDEPATH += \ # of custom MAVLink messages of this project. It will also # create a QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use # within the actual code. -exists(user_config.pri) { +exists(user_config.pri) { include(user_config.pri) message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----") message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF) message("------------------------------------------------------------------------") } INCLUDEPATH += $$MAVLINKPATH -isEmpty(MAVLINK_CONF) { +isEmpty(MAVLINK_CONF) { INCLUDEPATH += $$MAVLINKPATH/common } else { INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF @@ -166,7 +166,7 @@ FORMS += src/ui/MainWindow.ui \ src/ui/Linechart.ui \ src/ui/UASView.ui \ src/ui/ParameterInterface.ui \ - src/ui/WaypointList.ui \ + src/ui/WaypointList.ui \ src/ui/ObjectDetectionView.ui \ src/ui/JoystickWidget.ui \ src/ui/DebugConsole.ui \ @@ -200,8 +200,8 @@ FORMS += src/ui/MainWindow.ui \ src/ui/map/QGCMapTool.ui \ src/ui/map/QGCMapToolBar.ui \ src/ui/QGCMAVLinkInspector.ui \ - src/ui/WaypointViewOnlyView.ui \ - src/ui/WaypointEditableView.ui \ + src/ui/WaypointViewOnlyView.ui \ + src/ui/WaypointEditableView.ui \ src/ui/mavlink/QGCMAVLinkMessageSender.ui \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \ src/ui/QGCPluginHost.ui \ @@ -226,7 +226,11 @@ FORMS += src/ui/MainWindow.ui \ src/ui/QGCHilXPlaneConfiguration.ui \ src/ui/designer/QGCComboBox.ui \ src/ui/designer/QGCTextLabel.ui \ - src/ui/uas/UASQuickView.ui + src/ui/uas/UASQuickView.ui \ + src/ui/uas/UASQuickViewItemSelect.ui \ + src/ui/uas/UASActionsWidget.ui \ + src/ui/QGCTabbedInfoView.ui \ + src/ui/UASRawStatusView.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -275,7 +279,7 @@ HEADERS += src/MG.h \ src/comm/UDPLink.h \ src/ui/ParameterInterface.h \ src/ui/WaypointList.h \ - src/Waypoint.h \ + src/Waypoint.h \ src/ui/ObjectDetectionView.h \ src/input/JoystickInput.h \ src/ui/JoystickWidget.h \ @@ -344,7 +348,7 @@ HEADERS += src/MG.h \ src/ui/MAVLinkDecoder.h \ src/ui/WaypointViewOnlyView.h \ src/ui/WaypointViewOnlyView.h \ - src/ui/WaypointEditableView.h \ + src/ui/WaypointEditableView.h \ src/ui/QGCRGBDView.h \ src/ui/mavlink/QGCMAVLinkMessageSender.h \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \ @@ -375,13 +379,21 @@ HEADERS += src/MG.h \ src/ui/dockwidgettitlebareventfilter.h \ src/ui/uas/UASQuickView.h \ src/ui/uas/UASQuickViewItem.h \ - src/ui/linechart/ChartPlot.h + src/ui/linechart/ChartPlot.h \ + src/ui/uas/UASQuickViewItemSelect.h \ + src/ui/uas/UASQuickViewTextItem.h \ + src/ui/uas/UASQuickViewGaugeItem.h \ + src/ui/uas/UASActionsWidget.h \ + src/ui/designer/QGCRadioChannelDisplay.h \ + src/ui/QGCTabbedInfoView.h \ + src/ui/UASRawStatusView.h \ + src/ui/PrimaryFlightDisplay.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h -contains(DEPENDENCIES_PRESENT, osg) { +contains(DEPENDENCIES_PRESENT, osg) { message("Including headers for OpenSceneGraph") - + # Enable only if OpenSceneGraph is available HEADERS += src/ui/map3D/gpl.h \ src/ui/map3D/CameraParams.h \ @@ -414,9 +426,9 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { src/ui/map3D/ObstacleGroupNode.h \ src/ui/map3D/GLOverlayGeode.h } -contains(DEPENDENCIES_PRESENT, libfreenect) { +contains(DEPENDENCIES_PRESENT, libfreenect) { message("Including headers for libfreenect") - + # Enable only if libfreenect is available HEADERS += src/input/Freenect.h } @@ -543,15 +555,23 @@ SOURCES += src/main.cc \ src/ui/dockwidgettitlebareventfilter.cpp \ src/ui/uas/UASQuickViewItem.cc \ src/ui/uas/UASQuickView.cc \ - src/ui/linechart/ChartPlot.cc + src/ui/linechart/ChartPlot.cc \ + src/ui/uas/UASQuickViewTextItem.cc \ + src/ui/uas/UASQuickViewGaugeItem.cc \ + src/ui/uas/UASQuickViewItemSelect.cc \ + src/ui/uas/UASActionsWidget.cpp \ + src/ui/designer/QGCRadioChannelDisplay.cpp \ + src/ui/QGCTabbedInfoView.cpp \ + src/ui/UASRawStatusView.cpp \ + src/ui/PrimaryFlightDisplay.cpp # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc # Enable OSG only if it has been found -contains(DEPENDENCIES_PRESENT, osg) { +contains(DEPENDENCIES_PRESENT, osg) { message("Including sources for OpenSceneGraph") - + # Enable only if OpenSceneGraph is available SOURCES += src/ui/map3D/gpl.cc \ src/ui/map3D/CameraParams.cc \ @@ -576,9 +596,9 @@ contains(DEPENDENCIES_PRESENT, osg) { src/ui/map3D/TerrainParamDialog.cc \ src/ui/map3D/ImageryParamDialog.cc - contains(DEPENDENCIES_PRESENT, osgearth) { + contains(DEPENDENCIES_PRESENT, osgearth) { message("Including sources for osgEarth") - + # Enable only if OpenSceneGraph is available SOURCES += } @@ -591,9 +611,9 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { src/ui/map3D/ObstacleGroupNode.cc \ src/ui/map3D/GLOverlayGeode.cc } -contains(DEPENDENCIES_PRESENT, libfreenect) { +contains(DEPENDENCIES_PRESENT, libfreenect) { message("Including sources for libfreenect") - + # Enable only if libfreenect is available SOURCES += src/input/Freenect.cc } @@ -602,7 +622,7 @@ contains(DEPENDENCIES_PRESENT, libfreenect) { RESOURCES += qgroundcontrol.qrc # Include RT-LAB Library -win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) { +win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) { message("Building support for Opal-RT") LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \ -lOpalApi @@ -676,3 +696,7 @@ win32-msvc2008|win32-msvc2010|win32-msvc2012 { } unix:!macx:!symbian: LIBS += -losg + +OTHER_FILES += \ + dongfang_notes.txt \ + src/ui/dongfang-scrapyard.txt diff --git a/src/QGCCore.cc b/src/QGCCore.cc index 221071d4c7312b2135be2461e6a25c1863a43bb9..d58f07f5c964e95b06d55c4ec33ee3927be64f9e 100644 --- a/src/QGCCore.cc +++ b/src/QGCCore.cc @@ -200,7 +200,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv) QGCCore::~QGCCore() { //mainWindow->storeSettings(); - mainWindow->close(); + //mainWindow->close(); //mainWindow->deleteLater(); // Delete singletons // First systems @@ -208,7 +208,8 @@ QGCCore::~QGCCore() // then links delete LinkManager::instance(); // Finally the main window - delete MainWindow::instance(); + //delete MainWindow::instance(); + //The main window now autodeletes on close. } /** diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 4c2e682913595215a90cf4b4a6ebf6f86227f496..0cd15b3124b4b9feac1e6355e61b9fb55e401bcd 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -232,6 +232,8 @@ signals: /** @brief Communication error occured */ void communicationError(const QString& linkname, const QString& error); + void communicationUpdate(const QString& linkname, const QString& text); + /** @brief destroying element */ void deleteLink(LinkInterface* const link); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index e8c4a2a88b6daf8d0e5228436e66f32145f3e023..ae2cde0a79201b2ef0d84308b87ca5881cb61379 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -20,7 +20,6 @@ #ifdef _WIN32 #include "windows.h" #endif - #ifdef _WIN32 #include #endif @@ -394,7 +393,13 @@ void SerialLink::writeSettings() void SerialLink::run() { // Initialize the connection - hardwareConnect(); + if (!hardwareConnect()) + { + //Need to error out here. + emit communicationError(getName(),"Error connecting: " + port->errorString()); + return; + + } // Qt way to make clear what a while(1) loop does quint64 msecs = QDateTime::currentMSecsSinceEpoch(); @@ -402,7 +407,7 @@ void SerialLink::run() quint64 bytes = 0; bool triedreset = false; bool triedDTR = false; - int timeout = 2500; + int timeout = 5000; forever { { @@ -438,6 +443,7 @@ void SerialLink::run() if (!triedDTR && triedreset) { triedDTR = true; + communicationUpdate(getName(),"No data to receive on COM port. Attempting to reset via DTR signal"); qDebug() << "No data!!! Attempting reset via DTR."; port->setDtr(true); this->msleep(250); @@ -446,11 +452,13 @@ void SerialLink::run() else if (!triedreset) { qDebug() << "No data!!! Attempting reset via reboot command."; + communicationUpdate(getName(),"No data to receive on COM port. Assuming possible terminal mode, attempting to reset via \"reboot\" command"); port->write("reboot\r\n",8); triedreset = true; } else { + communicationUpdate(getName(),"No data to receive on COM port...."); qDebug() << "No data!!!"; } } @@ -661,7 +669,14 @@ bool SerialLink::hardwareConnect() port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead); connectionStartTime = MG::TIME::getGroundTimeNow(); - port->open(); + if (!port->open()) + { + emit communicationUpdate(getName(),"Error opening port: " + port->errorString()); + } + else + { + emit communicationUpdate(getName(),"Opened port!"); + } bool connectionUp = isConnected(); if(connectionUp) { diff --git a/src/uas/ArduPilotMegaMAV.h b/src/uas/ArduPilotMegaMAV.h index f0091aa15f29d518c6ab019377c00b39294401fd..61f4ac2f9b4665e15caee5e0d556bd363771c44b 100644 --- a/src/uas/ArduPilotMegaMAV.h +++ b/src/uas/ArduPilotMegaMAV.h @@ -25,9 +25,7 @@ This file is part of the QGROUNDCONTROL project #define ARDUPILOTMEGAMAV_H #include "UAS.h" -#include "ardupilotmega/mavlink_msg_mount_configure.h" -#include "ardupilotmega/mavlink_msg_mount_control.h" -#include "ardupilotmega/mavlink_msg_mount_status.h" + class ArduPilotMegaMAV : public UAS { Q_OBJECT diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 739334d6780d61ca22f9d578ceb8e6b74f7fc01f..f44bfb65ee7cfb59eb0a0543d11a93bc957d2924 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -39,16 +39,37 @@ */ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), uasId(id), - startTime(QGC::groundTimeMilliseconds()), - commStatus(COMM_DISCONNECTED), - name(""), - autopilot(-1), links(new QList()), unknownPackets(), mavlink(protocol), - waypointManager(this), + commStatus(COMM_DISCONNECTED), + receiveDropRate(0), + sendDropRate(0), + statusTimeout(new QTimer(this)), + + name(""), + type(MAV_TYPE_GENERIC), + airframe(QGC_AIRFRAME_GENERIC), + autopilot(-1), + systemIsArmed(false), + mode(-1), + // custom_mode not initialized + navMode(-1), + status(-1), + // shortModeText not initialized + // shortStateText not initialized + + // actuatorValues not initialized + // actuatorNames not initialized + // motorValues not initialized + // motorNames mnot initialized thrustSum(0), thrustMax(10), + + // batteryType not initialized + // cells not initialized + // fullVoltage not initialized + // emptyVoltage not initialized startVoltage(-1.0f), tickVoltage(10.5f), lastTickVoltageValue(13.0f), @@ -57,11 +78,15 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), warnLevelPercent(20.0f), currentVoltage(12.6f), lpVoltage(12.0f), + currentCurrent(0.4f), batteryRemainingEstimateEnabled(true), - mode(-1), - status(-1), - navMode(-1), + // chargeLevel not initialized + // timeRemaining not initialized + lowBattAlarm(false), + + startTime(QGC::groundTimeMilliseconds()), onboardTimeOffset(0), + controlRollManual(true), controlPitchManual(true), controlYawManual(true), @@ -70,10 +95,11 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), manualPitchAngle(0), manualYawAngle(0), manualThrust(0), - receiveDropRate(0), - sendDropRate(0), - lowBattAlarm(false), + positionLock(false), + isLocalPositionKnown(false), + isGlobalPositionKnown(false), + localX(0.0), localY(0.0), localZ(0.0), @@ -81,7 +107,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), latitude_gps(0.0), longitude_gps(0.0), altitude_gps(0.0), - statusTimeout(new QTimer(this)), + nedPosGlobalOffset(0,0,0), + nedAttGlobalOffset(0,0,0), + + + waypointManager(this), + #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) receivedOverlayTimestamp(0.0), receivedObstacleListTimestamp(0.0), @@ -89,18 +120,17 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), receivedPointCloudTimestamp(0.0), receivedRGBDImageTimestamp(0.0), #endif - paramsOnceRequested(false), - airframe(QGC_AIRFRAME_GENERIC), + attitudeKnown(false), - paramManager(NULL), attitudeStamped(false), lastAttitude(0), + + paramsOnceRequested(false), + paramManager(NULL), + simulation(0), - isLocalPositionKnown(false), - isGlobalPositionKnown(false), - systemIsArmed(false), - nedPosGlobalOffset(0,0,0), - nedAttGlobalOffset(0,0,0), + + // The protected members. connectionLost(false), lastVoltageWarning(0), lastNonNullTime(0), @@ -109,7 +139,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), sensorHil(false), lastSendTimeGPS(0), lastSendTimeSensors(0) - { for (unsigned int i = 0; i<255;++i) { @@ -123,7 +152,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings())); statusTimeout->start(500); readSettings(); - type = MAV_TYPE_GENERIC; // Initial signals emit disarmed(); emit armingChanged(false); @@ -447,7 +475,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) QString audiomodeText = getAudioModeTextFor(static_cast(state.base_mode)); - if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT) { statechanged = true; @@ -539,7 +566,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) lpVoltage = filterVoltage(currentVoltage); tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage; - // We don't want to tick above the threshold if (tickLowpassVoltage > tickVoltage) { @@ -567,20 +593,23 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) { chargeLevel = state.battery_remaining; } - emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining); + + emit batteryChanged(this, lpVoltage, currentCurrent, getChargeLevel(), timeRemaining); emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time); - emit voltageChanged(message.sysid, currentVoltage); + // emit voltageChanged(message.sysid, currentVoltage); emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time); // And if the battery current draw is measured, log that also. if (state.current_battery != -1) { - emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time); + currentCurrent = ((double)state.current_battery)/100.0f; + emit valueChanged(uasId, name.arg("battery_current"), "A", currentCurrent, time); } // LOW BATTERY ALARM if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3)) { + // An audio alarm. Does not generate any signals. startLowBattAlarm(); } else @@ -644,7 +673,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) attitudeKnown = true; emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time); - emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); + emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); } } break; @@ -682,8 +711,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time); } - emit altitudeChanged(uasId, hud.alt); - emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time); + // The primary altitude is the one that the UAV uses for navigation. + // We assume! that the HUD message reports that as altitude. + emit primaryAltitudeChanged(this, hud.alt, time); + + emit primarySpeedChanged(this, hud.airspeed, time); + emit gpsSpeedChanged(this, hud.groundspeed, time); + emit climbRateChanged(this, hud.climb, time); } break; case MAVLINK_MSG_ID_LOCAL_POSITION_NED: @@ -697,7 +731,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // Emit position always with component ID emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); - if (!wrongComponent) { localX = pos.x; @@ -705,9 +738,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) localZ = pos.z; // Emit - emit localPositionChanged(this, pos.x, pos.y, pos.z, time); - emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); + emit velocityChanged_NED(this, pos.vx, pos.vy, pos.vz, time); // Set internal state if (!positionLock) { @@ -735,18 +767,29 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_global_position_int_t pos; mavlink_msg_global_position_int_decode(&message, &pos); quint64 time = getUnixTime(); - //latitude = pos.lat/(double)1E7; setLatitude(pos.lat/(double)1E7); - //longitude = pos.lon/(double)1E7; setLongitude(pos.lon/(double)1E7); - //altitude = pos.alt/1000.0; + + // dongfang: Beware. There are 2 altitudes in this message; neither is the primary. + // pos.alt is GPS altitude and pos.relative_alt is above-home altitude. + // It would be nice if APM could be modified to present the primary (mix) alt. instead + // of the GPS alt. in this message. setAltitude(pos.alt/1000.0); + globalEstimatorActive = true; + speedX = pos.vx/100.0; speedY = pos.vy/100.0; speedZ = pos.vz/100.0; + emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time); - emit speedChanged(this, speedX, speedY, speedZ, time); + // dongfang: The altitude is GPS altitude. Bugger. It needs to be changed to primary. + emit gpsAltitudeChanged(this, getAltitude(), time); + // We had some frame mess here, global and local axes were mixed. + emit velocityChanged_NED(this, speedX, speedY, speedZ, time); + + double groundspeed = qSqrt(speedX*speedX+speedY*speedY); + emit gpsSpeedChanged(this, groundspeed, time); // Set internal state if (!positionLock) @@ -787,14 +830,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) longitude_gps = pos.lon/(double)1E7; altitude_gps = pos.alt/1000.0; + // If no GLOBAL_POSITION_INT messages ever received, use these raw GPS values instead. if (!globalEstimatorActive) { - //latitude = latitude_gps; setLatitude(latitude_gps); - //longitude = longitude_gps; setLongitude(longitude_gps); - //altitude = altitude_gps; setAltitude(altitude_gps); emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time); + emit gpsAltitudeChanged(this, getAltitude(), time); } positionLock = true; @@ -804,10 +846,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) float vel = pos.vel/100.0f; + // If no GLOBAL_POSITION_INT messages ever received, use these raw GPS values instead. if (!globalEstimatorActive) { if ((vel < 1000000) && !isnan(vel) && !isinf(vel)) { - emit speedChanged(this, vel, 0.0, 0.0, time); + //emit speedChanged(this, vel, 0.0, 0.0, time); + setGroundSpeed(vel); + // TODO: Other sources also? Actually this condition does not quite belong here. + emit gpsSpeedChanged(this, vel, time); } else { @@ -1350,6 +1396,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_nav_controller_output_t p; mavlink_msg_nav_controller_output_decode(&message,&p); setDistToWaypoint(p.wp_dist); + setBearingToWaypoint(p.nav_bearing); + //setAltitudeError(p.alt_error); + //setSpeedError(p.aspd_error); + //setCrosstrackingError(p.xtrack_error); + emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error); } break; case MAVLINK_MSG_ID_RAW_PRESSURE: @@ -1481,7 +1532,7 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptruasId,"groundSpeed","m/s",QVariant(val),getUnixTime()); + } + double getGroundSpeed() const + { + return groundSpeed; + } + Q_PROPERTY(double bearingToWaypoint READ getBearingToWaypoint WRITE setBearingToWaypoint NOTIFY bearingToWaypointChanged) + + // dongfang: There is not only one altitude; there are at least (APM) GPS altitude, mix altitude and mix-altitude relative to home. + // I have made this property refer to the mix-altitude ASL as this is the one actually used in navigation by APM. + Q_PROPERTY(double altitude READ getAltitude WRITE setAltitude NOTIFY altitudeChanged) void setLocalX(double val) { @@ -120,6 +126,7 @@ public: emit localXChanged(val,"localX"); emit valueChanged(this->uasId,"localX","M",QVariant(val),getUnixTime()); } + double getLocalX() const { return localX; @@ -153,6 +160,7 @@ public: emit latitudeChanged(val,"latitude"); emit valueChanged(this->uasId,"latitude","deg",QVariant(val),getUnixTime()); } + double getLatitude() const { return latitude; @@ -164,6 +172,7 @@ public: emit longitudeChanged(val,"longitude"); emit valueChanged(this->uasId,"longitude","deg",QVariant(val),getUnixTime()); } + double getLongitude() const { return longitude; @@ -172,7 +181,7 @@ public: void setAltitude(double val) { altitude = val; - emit altitudeChanged(val,"altitude"); + emit altitudeChanged(val, "altitude"); emit valueChanged(this->uasId,"altitude","M",QVariant(val),getUnixTime()); } @@ -197,6 +206,7 @@ public: { return isLocalPositionKnown; } + virtual bool globalPositionKnown() const { return isGlobalPositionKnown; @@ -214,6 +224,19 @@ public: return distToWaypoint; } + void setBearingToWaypoint(double val) + { + bearingToWaypoint = val; + emit bearingToWaypointChanged(val,"bearingToWaypoint"); + emit valueChanged(this->uasId,"bearingToWaypoint","M",QVariant(val),getUnixTime()); + } + + double getBearingToWaypoint() const + { + return bearingToWaypoint; + } + + void setRoll(double val) { roll = val; @@ -246,6 +269,7 @@ public: { return yaw; } + bool getSelected() const; QVector3D getNedPosGlobalOffset() const { @@ -319,31 +343,43 @@ public: friend class UASWaypointManager; protected: //COMMENTS FOR TEST UNIT + /// LINK ID AND STATUS int uasId; ///< Unique system ID - unsigned char type; ///< UAS type (from type enum) - quint64 startTime; ///< The time the UAS was switched on - CommStatus commStatus; ///< Communication status - QString name; ///< Human-friendly name of the vehicle, e.g. bravo - int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + QMap components;///< IDs and names of all detected onboard components QList* links; ///< List of links this UAS can be reached by QList unknownPackets; ///< Packet IDs which are unknown and have been received MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance - BatteryType batteryType; ///< The battery type - int cells; ///< Number of cells - - UASWaypointManager waypointManager; + CommStatus commStatus; ///< Communication status + float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs) + float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS + quint64 lastHeartbeat; ///< Time of the last heartbeat message + QTimer* statusTimeout; ///< Timer for various status timeouts + /// BASIC UAS TYPE, NAME AND STATE + QString name; ///< Human-friendly name of the vehicle, e.g. bravo + unsigned char type; ///< UAS type (from type enum) + int airframe; ///< The airframe type + int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + bool systemIsArmed; ///< If the system is armed + uint8_t mode; ///< The current mode of the MAV + uint32_t custom_mode; ///< The current mode of the MAV + uint32_t navMode; ///< The current navigation mode of the MAV + int status; ///< The current status of the MAV + QString shortModeText; ///< Short textual mode description + QString shortStateText; ///< Short textual state description + + /// OUTPUT QList actuatorValues; QList actuatorNames; - QList motorValues; QList motorNames; - QMap components; ///< IDs and names of all detected onboard components - double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons - // Battery stats + // dongfang: This looks like a candidate for being moved off to a separate class. + /// BATTERY / ENERGY + BatteryType batteryType; ///< The battery type + int cells; ///< Number of cells float fullVoltage; ///< Voltage of the fully charged battery (100%) float emptyVoltage; ///< Voltage of the empty battery (0%) float startVoltage; ///< Voltage at system start @@ -354,15 +390,18 @@ protected: //COMMENTS FOR TEST UNIT float warnLevelPercent; ///< Warning level, in percent double currentVoltage; ///< Voltage currently measured float lpVoltage; ///< Low-pass filtered voltage + double currentCurrent; ///< Battery current currently measured bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life float chargeLevel; ///< Charge level of battery, in percent int timeRemaining; ///< Remaining time calculated based on previous and current - uint8_t mode; ///< The current mode of the MAV - uint32_t custom_mode; ///< The current mode of the MAV - int status; ///< The current status of the MAV - uint32_t navMode; ///< The current navigation mode of the MAV + bool lowBattAlarm; ///< Switch if battery is low + + + /// TIMEKEEPING + quint64 startTime; ///< The time the UAS was switched on quint64 onboardTimeOffset; + /// MANUAL CONTROL bool controlRollManual; ///< status flag, true if roll is controlled manually bool controlPitchManual; ///< status flag, true if pitch is controlled manually bool controlYawManual; ///< status flag, true if yaw is controlled manually @@ -372,16 +411,20 @@ protected: //COMMENTS FOR TEST UNIT double manualPitchAngle; ///< Pitch angle set by human pilot (radians) double manualYawAngle; ///< Yaw angle set by human pilot (radians) double manualThrust; ///< Thrust set by human pilot (radians) - float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs) - float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS - bool lowBattAlarm; ///< Switch if battery is low + + /// POSITION bool positionLock; ///< Status if position information is available or not + bool isLocalPositionKnown; ///< If the local position has been received for this MAV + bool isGlobalPositionKnown; ///< If the global position has been received for this MAV + double localX; double localY; double localZ; + double latitude; ///< Global latitude as estimated by position estimator double longitude; ///< Global longitude as estimated by position estimator double altitude; ///< Global altitude as estimated by position estimator + double satelliteCount; ///< Number of satellites visible to raw GPS bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position double latitude_gps; ///< Global latitude as estimated by raw GPS @@ -390,13 +433,26 @@ protected: //COMMENTS FOR TEST UNIT double speedX; ///< True speed in X axis double speedY; ///< True speed in Y axis double speedZ; ///< True speed in Z axis + + QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin + QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin + + /// WAYPOINT NAVIGATION double distToWaypoint; ///< Distance to next waypoint + double groundSpeed; ///< GPS Groundspeed + double bearingToWaypoint; ///< Bearing to next waypoint + UASWaypointManager waypointManager; + + /// ATTITUDE + bool attitudeKnown; ///< True if attitude was received, false else + bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV + quint64 lastAttitude; ///< Timestamp of last attitude measurement double roll; double pitch; double yaw; - quint64 lastHeartbeat; ///< Time of the last heartbeat message - QTimer* statusTimeout; ///< Timer for various status timeouts + // dongfang: This looks like a candidate for being moved off to a separate class. + /// IMAGING int imageSize; ///< Image size being transmitted (bytes) int imagePackets; ///< Number of data packets being sent for this image int imagePacketsArrived; ///< Number of data packets recieved @@ -431,21 +487,13 @@ protected: //COMMENTS FOR TEST UNIT qreal receivedRGBDImageTimestamp; #endif + /// PARAMETERS QMap* > parameters; ///< All parameters bool paramsOnceRequested; ///< If the parameter list has been read at least once - int airframe; ///< The airframe type - bool attitudeKnown; ///< True if attitude was received, false else QGCUASParamManager* paramManager; ///< Parameter manager class - QString shortStateText; ///< Short textual state description - QString shortModeText; ///< Short textual mode description - bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV - quint64 lastAttitude; ///< Timestamp of last attitude measurement + + /// SIMULATION QGCHilLink* simulation; ///< Hardware in the loop simulation link - bool isLocalPositionKnown; ///< If the local position has been received for this MAV - bool isGlobalPositionKnown; ///< If the global position has been received for this MAV - bool systemIsArmed; ///< If the system is armed - QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin - QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin public: /** @brief Set the current battery type */ @@ -646,12 +694,12 @@ public slots: void enableHilXPlane(bool enable); /** @brief Send the full HIL state to the MAV */ - void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed, - float pitchspeed, float yawspeed, double lat, double lon, double alt, + void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate, + float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt, float vx, float vy, float vz, float xacc, float yacc, float zacc); /** @brief RAW sensors for sensor HIL */ - void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed, + void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollRotationRate, float pitchRotationRate, float yawRotationRate, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint16 fields_changed); /** @@ -810,15 +858,17 @@ signals: void longitudeChanged(double val,QString name); void latitudeChanged(double val,QString name); void altitudeChanged(double val,QString name); - void altitudeChanged(int uasid, double altitude); void rollChanged(double val,QString name); void pitchChanged(double val,QString name); void yawChanged(double val,QString name); void satelliteCountChanged(double val,QString name); void distToWaypointChanged(double val,QString name); + void groundSpeedChanged(double val, QString name); + void bearingToWaypointChanged(double val,QString name); - - + //void primaryAltitudeChanged(UASInterface*, double altitude, quint64 usec); + //void gpsAltitudeChanged(UASInterface*, double altitude, quint64 usec); + //void velocityChanged_NED(UASInterface*, double vx, double vy, double vz, quint64 usec); protected: /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ quint64 getUnixTime(quint64 time=0); @@ -826,6 +876,7 @@ protected: quint64 getUnixTimeFromMs(quint64 time); /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */ quint64 getUnixReferenceTime(quint64 time); + int componentID[256]; bool componentMulti[256]; bool connectionLost; ///< Flag indicates a timed out connection diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 06a03b70a893929e0a9adc373a429f0f856fca06..83f07f7497dd97faf8e9256048eece0b6ab73fcb 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -51,6 +51,42 @@ This file is part of the QGROUNDCONTROL project #endif #endif +enum BatteryType +{ + NICD = 0, + NIMH = 1, + LIION = 2, + LIPOLY = 3, + LIFE = 4, + AGZN = 5 +}; ///< The type of battery used + +/* +enum SpeedMeasurementSource +{ + PRIMARY_SPEED = 0, // ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed. + GROUNDSPEED_BY_UAV = 1, // Ground speed as reported by UAS + GROUNDSPEED_BY_GPS = 2, // Ground speed as calculated from received GPS velocity data + LOCAL_SPEED = 3 +}; ///< For velocity data, the data source + +enum AltitudeMeasurementSource +{ + PRIMARY_ALTITUDE = 0, // ArduPlane: air and ground speed mix. This is the altitude used for navigastion. + BAROMETRIC_ALTITUDE = 1, // Altitude is pressure altitude. Ardupilot reports no altitude purely by barometer, + // however when ALT_MIX==1, mix-altitude is purely barometric. + GPS_ALTITUDE = 2 // GPS ASL altitude +}; ///< For altitude data, the data source + +// TODO!!! The different frames are probably represented elsewhere. There should really only +// be one set of frames. We also need to keep track of the home alt. somehow. +enum AltitudeMeasurementFrame +{ + ABSOLUTE = 0, // Altitude is pressure altitude + ABOVE_HOME_POSITION = 1 +}; ///< For altitude data, a reference frame +*/ + /** * @brief Interface for all robots. * @@ -470,14 +506,14 @@ signals: * @param percent remaining capacity in percent * @param seconds estimated remaining flight time in seconds */ - void batteryChanged(UASInterface* uas, double voltage, double percent, int seconds); + void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds); void statusChanged(UASInterface* uas, QString status); void actuatorChanged(UASInterface*, int actId, double value); void thrustChanged(UASInterface*, double thrust); void heartbeat(UASInterface* uas); void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec); void attitudeChanged(UASInterface*, int component, double roll, double pitch, double yaw, quint64 usec); - void attitudeSpeedChanged(int uas, double rollspeed, double pitchspeed, double yawspeed, quint64 usec); + void attitudeRotationRatesChanged(int uas, double rollrate, double pitchrate, double yawrate, quint64 usec); void attitudeThrustSetPointChanged(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec); /** @brief The MAV set a new setpoint in the local (not body) NED X, Y, Z frame */ void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec); @@ -486,10 +522,21 @@ signals: void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec); void localPositionChanged(UASInterface*, int component, double x, double y, double z, quint64 usec); void globalPositionChanged(UASInterface*, double lat, double lon, double alt, quint64 usec); - void altitudeChanged(int uasid, double altitude); + void primaryAltitudeChanged(UASInterface*, double altitude, quint64 usec); + void gpsAltitudeChanged(UASInterface*, double altitude, quint64 usec); /** @brief Update the status of one satellite used for localization */ void gpsSatelliteStatusChanged(int uasid, int satid, float azimuth, float direction, float snr, bool used); - void speedChanged(UASInterface*, double x, double y, double z, quint64 usec); + + // The horizontal speed (a scalar) + void primarySpeedChanged(UASInterface*, double speed, quint64 usec); + void gpsSpeedChanged(UASInterface*, double speed, quint64 usec); + // The vertical speed (a scalar) + void climbRateChanged(UASInterface*, double climb, quint64 usec); + // Consider adding a MAV_FRAME parameter to this; could help specifying what the 3 scalars are. + void velocityChanged_NED(UASInterface*, double vx, double vy, double vz, quint64 usec); + + void navigationControllerErrorsChanged(UASInterface*, double altitudeError, double speedError, double xtrackError); + void imageStarted(int imgid, int width, int height, int depth, int channels); void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex); /** @brief Emit the new system type */ diff --git a/src/uas/senseSoarMAV.cpp b/src/uas/senseSoarMAV.cpp index 031eeb3e9c6b204c202335103818fdf1520eab73..fc1ad320310d8d65e609c08e9c8b6f9a8ee9edc7 100644 --- a/src/uas/senseSoarMAV.cpp +++ b/src/uas/senseSoarMAV.cpp @@ -41,7 +41,7 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message emit valueChanged(uasId, "rollspeed", "rad/s", this->m_rotVel[0], time); emit valueChanged(uasId, "pitchspeed", "rad/s", this->m_rotVel[1], time); emit valueChanged(uasId, "yawspeed", "rad/s", this->m_rotVel[2], time); - emit attitudeSpeedChanged(uasId, this->m_rotVel[0], this->m_rotVel[1], this->m_rotVel[2], time); + emit attitudeRotationRatesChanged(uasId, this->m_rotVel[0], this->m_rotVel[1], this->m_rotVel[2], time); break; } case MAVLINK_MSG_ID_LLC_OUT: // low level controller output @@ -62,7 +62,7 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message mavlink_obs_air_temp_t airTMsg; mavlink_msg_obs_air_temp_decode(&message,&airTMsg); quint64 time = getUnixTime(); - emit valueChanged(uasId, "Air Temp", "°", airTMsg.airT, time); + emit valueChanged(uasId, "Air Temp", "°", airTMsg.airT, time); break; } case MAVLINK_MSG_ID_OBS_AIR_VELOCITY: @@ -211,4 +211,4 @@ void senseSoarMAV::quat2euler(const double *quat, double &roll, double &pitch, d pitch = std::asin(qMax(-1.0,qMin(1.0,2*(quat[0]*quat[2] - quat[1]*quat[3])))); yaw = std::atan2(2*(quat[1]*quat[2] + quat[0]*quat[3]),quat[0]*quat[0] + quat[1]*quat[1] - quat[2]*quat[2] - quat[3]*quat[3]); return; -} \ No newline at end of file +} diff --git a/src/ui/DebugConsole.cc b/src/ui/DebugConsole.cc index 8e856aa4f15c0d511e19e4fd266a0cc8da73439a..c89fc3811428bf224c11b8e75b01ea8688717575 100644 --- a/src/ui/DebugConsole.cc +++ b/src/ui/DebugConsole.cc @@ -215,6 +215,12 @@ void DebugConsole::removeLink(LinkInterface* const linkInterface) } if (linkInterface == currLink) currLink = NULL; } +void DebugConsole::linkStatusUpdate(const QString& name,const QString& text) +{ + m_ui->receiveText->appendPlainText(text); + // Ensure text area scrolls correctly + m_ui->receiveText->ensureCursorVisible(); +} void DebugConsole::linkSelected(int linkId) { @@ -222,6 +228,7 @@ void DebugConsole::linkSelected(int linkId) if (currLink) { disconnect(currLink, SIGNAL(bytesReceived(LinkInterface*,QByteArray)), this, SLOT(receiveBytes(LinkInterface*, QByteArray))); disconnect(currLink, SIGNAL(connected(bool)), this, SLOT(setConnectionState(bool))); + disconnect(currLink,SIGNAL(communicationUpdate(QString,QString)),this,SLOT(linkStatusUpdate(QString,QString))); } // Clear data m_ui->receiveText->clear(); @@ -230,6 +237,7 @@ void DebugConsole::linkSelected(int linkId) currLink = links[linkId]; connect(currLink, SIGNAL(bytesReceived(LinkInterface*,QByteArray)), this, SLOT(receiveBytes(LinkInterface*, QByteArray))); connect(currLink, SIGNAL(connected(bool)), this, SLOT(setConnectionState(bool))); + connect(currLink,SIGNAL(communicationUpdate(QString,QString)),this,SLOT(linkStatusUpdate(QString,QString))); setConnectionState(currLink->isConnected()); } diff --git a/src/ui/DebugConsole.h b/src/ui/DebugConsole.h index 4a7cf6b8debcf54ef2e5320510d981be32013228..75365f39c812418c6275e60cc0e1552659170775 100644 --- a/src/ui/DebugConsole.h +++ b/src/ui/DebugConsole.h @@ -96,6 +96,8 @@ public slots: /** @brief A new special symbol is selected */ void specialSymbolSelected(const QString& text); + void linkStatusUpdate(const QString& name,const QString& text); + protected slots: /** @brief Draw information overlay */ void paintEvent(QPaintEvent *event); diff --git a/src/ui/DebugConsole.ui b/src/ui/DebugConsole.ui index 772427f5c06f7633dd0edecda2374e5b9adbbf30..8496945d9998469411c88e3c64c781717b5ac11e 100644 --- a/src/ui/DebugConsole.ui +++ b/src/ui/DebugConsole.ui @@ -110,6 +110,9 @@ 50 + + true + 60 diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 7bbdeac9e6cdb89996d6949a8dd8e0a1538de374..5423828735d4552a2120eeca8e9fa29f52acbea6 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -179,7 +179,10 @@ HSIDisplay::HSIDisplay(QWidget *parent) : connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage())); statusClearTimer.start(3000); - setActiveUAS(UASManager::instance()->getActiveUAS()); + if (UASManager::instance()->getActiveUAS()) + { + setActiveUAS(UASManager::instance()->getActiveUAS()); + } setFocusPolicy(Qt::StrongFocus); } @@ -918,7 +921,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) disconnect(this->uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64))); disconnect(this->uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64))); disconnect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float))); - disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); + disconnect(this->uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); disconnect(this->uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool))); @@ -949,7 +952,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64))); connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64))); connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float))); - connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool))); diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index fcd3b28ebfaa6f81ac84f4b3a9b065d43cf99843..23ac8405127e0d2107c75d38698855307532fd1f 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -61,7 +61,7 @@ This file is part of the QGROUNDCONTROL project * @param parent */ HUD::HUD(int width, int height, QWidget* parent) - : QGLWidget(QGLFormat(QGL::SampleBuffers), parent), + : QWidget(parent), uas(NULL), yawInt(0.0f), mode(tr("UNKNOWN MODE")), @@ -114,8 +114,8 @@ HUD::HUD(int width, int height, QWidget* parent) load(0.0f), offlineDirectory(""), nextOfflineImage(""), - hudInstrumentsEnabled(true), - videoEnabled(false), + HUDInstrumentsEnabled(true), + videoEnabled(true), xImageFactor(1.0), yImageFactor(1.0), imageLoggingEnabled(false), @@ -139,7 +139,15 @@ HUD::HUD(int width, int height, QWidget* parent) connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD())); // Resize to correct size and fill with image - resize(this->width(), this->height()); + QWidget::resize(this->width(), this->height()); + //glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits()); + + // Set size once + //setFixedSize(fill.size()); + //setMinimumSize(fill.size()); + //setMaximumSize(fill.size()); + // Lock down the size + //setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); fontDatabase = QFontDatabase(); const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app @@ -217,7 +225,7 @@ void HUD::showEvent(QShowEvent* event) { // React only to internal (pre-display) // events - QGLWidget::showEvent(event); + QWidget::showEvent(event); refreshTimer->start(updateInterval); emit visibilityChanged(true); } @@ -227,7 +235,7 @@ void HUD::hideEvent(QHideEvent* event) // React only to internal (pre-display) // events refreshTimer->stop(); - QGLWidget::hideEvent(event); + QWidget::hideEvent(event); emit visibilityChanged(false); } @@ -235,7 +243,7 @@ void HUD::contextMenuEvent (QContextMenuEvent* event) { QMenu menu(this); // Update actions - enableHUDAction->setChecked(hudInstrumentsEnabled); + enableHUDAction->setChecked(HUDInstrumentsEnabled); enableVideoAction->setChecked(videoEnabled); menu.addAction(enableHUDAction); @@ -251,7 +259,7 @@ void HUD::createActions() enableHUDAction = new QAction(tr("Enable HUD"), this); enableHUDAction->setStatusTip(tr("Show the HUD instruments in this window")); enableHUDAction->setCheckable(true); - enableHUDAction->setChecked(hudInstrumentsEnabled); + enableHUDAction->setChecked(HUDInstrumentsEnabled); connect(enableHUDAction, SIGNAL(triggered(bool)), this, SLOT(enableHUDInstruments(bool))); enableVideoAction = new QAction(tr("Enable Video Live feed"), this); @@ -278,16 +286,16 @@ void HUD::setActiveUAS(UASInterface* uas) { if (this->uas != NULL) { // Disconnect any previously connected active MAV - disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); - disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); - disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int))); + disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*, double, double, double, quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); + disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int, double, double, double, quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); + disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int))); disconnect(this->uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString))); disconnect(this->uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); disconnect(this->uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*))); disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); disconnect(this->uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); - disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); + disconnect(this->uas, SIGNAL(velocityChanged_NEDspeedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); disconnect(this->uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int))); // Try to disconnect the image link @@ -303,14 +311,14 @@ void HUD::setActiveUAS(UASInterface* uas) // Setup communication connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); - connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int))); + connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int))); connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString))); connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); connect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*))); connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); - connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int))); // Try to connect the image link @@ -355,10 +363,11 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p } } -void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) +void HUD::updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds) { Q_UNUSED(uas); Q_UNUSED(seconds); + Q_UNUSED(current); fuelStatus = tr("BAT [%1% | %2V]").arg(percent, 2, 'f', 0, QChar('0')).arg(voltage, 4, 'f', 1, QChar('0')); if (percent < 20.0f) { fuelColor = warningColor; @@ -463,73 +472,6 @@ float HUD::refToScreenY(float y) return (scalingFactor * y); } -/** - * This functions works in the OpenGL view, which is already translated by - * the x and y center offsets. - * - */ -void HUD::paintCenterBackground(float roll, float pitch, float yaw) -{ - Q_UNUSED(yaw); - - // Center indicator is 100 mm wide - float referenceWidth = 70.0; - float referenceHeight = 70.0; - - // HUD is assumed to be 200 x 150 mm - // so that positions can be hardcoded - // but can of course be scaled. - - double referencePositionX = vwidth / 2.0 - referenceWidth/2.0; - double referencePositionY = vheight / 2.0 - referenceHeight/2.0; - - //this->width()/2.0+(xCenterOffset*scalingFactor), this->height()/2.0+(yCenterOffset*scalingFactor); - - setupGLView(referencePositionX, referencePositionY, referenceWidth, referenceHeight); - - // Store current position in the model view - // the position will be restored after drawing - glMatrixMode(GL_MODELVIEW); - glPushMatrix(); - - // Move to the center of the window - glTranslatef(referenceWidth/2.0f,referenceHeight/2.0f,0); - - // Move based on the yaw difference - //glTranslatef(yaw, 0.0f, 0.0f); - - // Rotate based on the bank - glRotatef((roll/M_PI)*180.0f, 0.0f, 0.0f, 1.0f); - - // Translate in the direction of the rotation based - // on the pitch. On the 777, a pitch of 1 degree = 2 mm - //glTranslatef(0, ((-pitch/M_PI)*180.0f * vPitchPerDeg), 0); - glTranslatef(0.0f, (-pitch * vPitchPerDeg * 16.5f), 0.0f); - - // Ground - glColor3ub(179,102,0); - - glBegin(GL_POLYGON); - glVertex2f(-300,-900); - glVertex2f(-300,0); - glVertex2f(300,0); - glVertex2f(300,-900); - glVertex2f(-300,-900); - glEnd(); - - // Sky - glColor3ub(0,153,204); - - glBegin(GL_POLYGON); - glVertex2f(-300,0); - glVertex2f(-300,900); - glVertex2f(300,900); - glVertex2f(300,0); - glVertex2f(-300,0); - - glEnd(); -} - /** * Paint text on top of the image and OpenGL drawings * @@ -563,29 +505,6 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa painter->setPen(prevPen); } -void HUD::initializeGL() -{ - bool antialiasing = true; - - // Antialiasing setup - if(antialiasing) { - glEnable(GL_MULTISAMPLE); - glEnable(GL_BLEND); - - glBlendFunc(GL_SRC_ALPHA,GL_ONE_MINUS_SRC_ALPHA); - - glEnable(GL_POINT_SMOOTH); - glEnable(GL_LINE_SMOOTH); - - glHint(GL_POINT_SMOOTH_HINT, GL_NICEST); - glHint(GL_LINE_SMOOTH_HINT, GL_NICEST); - } else { - glDisable(GL_BLEND); - glDisable(GL_POINT_SMOOTH); - glDisable(GL_LINE_SMOOTH); - } -} - /** * @param referencePositionX horizontal position in the reference mm-unit space * @param referencePositionY horizontal position in the reference mm-unit space @@ -599,23 +518,6 @@ void HUD::setupGLView(float referencePositionX, float referencePositionY, float // Translate and scale the GL view in the virtual reference coordinate units on the screen int pixelPositionX = (int)((referencePositionX * scalingFactor) + xCenterOffset); int pixelPositionY = this->height() - (referencePositionY * scalingFactor) + yCenterOffset - pixelHeight; - - //qDebug() << "Pixel x" << pixelPositionX << "pixelY" << pixelPositionY; - //qDebug() << "xCenterOffset:" << xCenterOffset << "yCenterOffest" << yCenterOffset - - - //The viewport is established at the correct pixel position and clips everything - // out of the desired instrument location - glViewport(pixelPositionX, pixelPositionY, pixelWidth, pixelHeight); - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); - - // The ortho projection is setup in a way that so that the drawing is done in the - // reference coordinate space - glOrtho(0, referenceWidth, 0, referenceHeight, -1, 1); - glMatrixMode(GL_MODELVIEW); - glLoadIdentity(); - //glScalef(scaleX, scaleY, 1.0f); } void HUD::paintRollPitchStrips() @@ -683,25 +585,13 @@ void HUD::paintHUD() scalingFactor = this->width()/vwidth; double scalingFactorH = this->height()/vheight; if (scalingFactorH < scalingFactor) scalingFactor = scalingFactorH; - - - - // OPEN GL PAINTING - // Store model view matrix to be able to reset it to the previous state - makeCurrent(); - glMatrixMode(GL_MODELVIEW); - glPushMatrix(); - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - // If video is enabled, get the next frame. - if (videoEnabled) - { - if (nextOfflineImage != "" && QFileInfo(nextOfflineImage).exists()) - { + // Fill with black background + if (videoEnabled) { + if (nextOfflineImage != "" && QFileInfo(nextOfflineImage).exists()) { qDebug() << __FILE__ << __LINE__ << "template image:" << nextOfflineImage; QImage fill = QImage(nextOfflineImage); - glImage = QGLWidget::convertToGLFormat(fill); + glImage = fill; // Reset to save load efforts nextOfflineImage = ""; @@ -712,31 +602,23 @@ void HUD::paintHUD() // And if either video or the data stream is enabled, draw the next frame. if (dataStreamEnabled || videoEnabled) { - glRasterPos2i(0, 0); xImageFactor = width() / (float)glImage.width(); yImageFactor = height() / (float)glImage.height(); float imageFactor = qMin(xImageFactor, yImageFactor); - glPixelZoom(imageFactor, imageFactor); // Resize to correct size and fill with image - glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits()); - //qDebug() << "DRAWING GL IMAGE"; - } - // But if no video frame should be shown, paint the sky/ground background. - else - { - // Blue / brown background - paintCenterBackground(roll, pitch, yawTrans); - } + // FIXME - glMatrixMode(GL_MODELVIEW); - glPopMatrix(); + } // END OF OPENGL PAINTING - // Paint all the instrument data using Qt. - if (hudInstrumentsEnabled) + if (HUDInstrumentsEnabled) { + + //glEnable(GL_MULTISAMPLE); + + // QT PAINTING //makeCurrent(); QPainter painter; painter.begin(this); @@ -908,11 +790,6 @@ void HUD::paintHUD() painter.begin(this); painter.end(); } - //glDisable(GL_MULTISAMPLE); - - - - //glFlush(); } } @@ -1322,20 +1199,6 @@ void HUD::drawCircle(float refX, float refY, float radius, float startDeg, float drawEllipse(refX, refY, radius, radius, startDeg, endDeg, lineWidth, color, painter); } -void HUD::resizeGL(int w, int h) -{ - if (isVisible()) { - glViewport(0, 0, w, h); - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); - glOrtho(0, w, 0, h, -1, 1); - glMatrixMode(GL_MODELVIEW); - glPolygonMode(GL_FRONT, GL_FILL); - //FIXME - paintHUD(); - } -} - void HUD::selectWaypoint(int uasId, int id) { Q_UNUSED(uasId); @@ -1390,7 +1253,7 @@ void HUD::setImageSize(int width, int height, int depth, int channels) { image->fill(0); } - glImage = QGLWidget::convertToGLFormat(*image); + glImage = *image; qDebug() << __FILE__ << __LINE__ << "Setting up image"; @@ -1441,7 +1304,7 @@ void HUD::commitRawDataToGL() } } - glImage = QGLWidget::convertToGLFormat(*newImage); + glImage = *newImage; delete image; image = newImage; // Switch buffers @@ -1486,7 +1349,7 @@ void HUD::selectOfflineDirectory() void HUD::enableHUDInstruments(bool enabled) { - hudInstrumentsEnabled = enabled; + HUDInstrumentsEnabled = enabled; } void HUD::enableVideo(bool enabled) @@ -1536,13 +1399,13 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s void HUD::copyImage() { - if (isVisible() && hudInstrumentsEnabled) + if (isVisible() && HUDInstrumentsEnabled) { //qDebug() << "HUD::copyImage()"; UAS* u = dynamic_cast(this->uas); if (u) { - this->glImage = QGLWidget::convertToGLFormat(u->getImage()); + this->glImage = u->getImage(); // Save to directory if logging is enabled if (imageLoggingEnabled) diff --git a/src/ui/HUD.h b/src/ui/HUD.h index 63568291e7217856dcb938bdad401c8360f74727..6dff3cc83492fa2239704d3338574c4e6bf48746 100644 --- a/src/ui/HUD.h +++ b/src/ui/HUD.h @@ -33,7 +33,7 @@ This file is part of the QGROUNDCONTROL project #define HUD_H #include -#include +#include #include #include #include @@ -48,7 +48,7 @@ This file is part of the QGROUNDCONTROL project * It can superimpose the HUD over the current live image stream (any arriving image stream will be auto- * matically used as background), or it draws the classic blue-brown background known from instruments. */ -class HUD : public QGLWidget +class HUD : public QWidget { Q_OBJECT public: @@ -56,10 +56,9 @@ public: ~HUD(); void setImageSize(int width, int height, int depth, int channels); - void resizeGL(int w, int h); + void resize(int w, int h); public slots: - void initializeGL(); void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE newTheme); /** @brief Set the currently monitored UAS */ @@ -70,7 +69,7 @@ public slots: /** @brief Attitude from one specific component / redundant autopilot */ void updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp); // void updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec); - void updateBattery(UASInterface*, double, double, int); + void updateBattery(UASInterface*, double, double, double, int); void receiveHeartbeat(UASInterface*); void updateThrust(UASInterface*, double); void updateLocalPosition(UASInterface*,double,double,double,quint64); @@ -99,7 +98,6 @@ public slots: protected slots: - void paintCenterBackground(float roll, float pitch, float yaw); void paintRollPitchStrips(); void paintPitchLines(float pitch, QPainter* painter); /** @brief Paint text on top of the image and OpenGL drawings */ @@ -185,7 +183,7 @@ protected: int warningBlinkRate; ///< Blink rate of warning messages, will be rounded to the refresh rate QTimer* refreshTimer; ///< The main timer, controls the update rate - QPainter* hudPainter; + QPainter* HUDPainter; QFont font; ///< The HUD font, per default the free Bitstream Vera SANS, which is very close to actual HUD fonts QFontDatabase fontDatabase;///< Font database, only used to load the TrueType font file (the HUD font is directly loaded from file rather than from the system) bool noCamera; ///< No camera images available, draw the ground/sky box to indicate the horizon @@ -219,7 +217,7 @@ protected: float load; QString offlineDirectory; QString nextOfflineImage; - bool hudInstrumentsEnabled; + bool HUDInstrumentsEnabled; bool videoEnabled; bool dataStreamEnabled; bool imageLoggingEnabled; diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index 1934025bd9ba3b9ed3aa99ab5a41b523bdb63bc2..b93fa9af5a8848e9195d8793a7c3dc1a51d720d0 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -200,7 +200,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 // Add field tree widget item uint8_t msgid = msg->msgid; - if (messageFilter.contains(msgid)) return; + //if (messageFilter.contains(msgid)) return; QString fieldName(messageInfo[msgid].fields[fieldid].name); QString fieldType; uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8; diff --git a/src/ui/MAVLinkDecoder.h b/src/ui/MAVLinkDecoder.h index 27969f53f8857127be6b089314630e394d243452..7031882e4f044a0ff7e23ba354a91407649132ca 100644 --- a/src/ui/MAVLinkDecoder.h +++ b/src/ui/MAVLinkDecoder.h @@ -21,6 +21,7 @@ signals: void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec); + //void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant value, const quint64 msec); public slots: diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index c29a4c62b47bad1d7d92fb6ae38778b96854e166..7c63bda454f94777ad69ce95981a275d85433958 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -61,6 +61,10 @@ This file is part of the QGROUNDCONTROL project #include "UASQuickView.h" #include "QGCDataPlot2D.h" #include "Linecharts.h" +#include "UASActionsWidget.h" +#include "QGCTabbedInfoView.h" +#include "UASRawStatusView.h" +#include "PrimaryFlightDisplay.h" #ifdef QGC_OSG_ENABLED #include "Q3DWidgetFactory.h" @@ -113,6 +117,7 @@ MainWindow::MainWindow(QWidget *parent): dockWidgetTitleBarEnabled(true), isAdvancedMode(false) { + this->setAttribute(Qt::WA_DeleteOnClose); hide(); } @@ -337,6 +342,16 @@ MainWindow::~MainWindow() } } // Delete all UAS objects + + + if (debugConsole) + { + delete debugConsole; + } + for (int i=0;ideleteLater(); + } } void MainWindow::resizeEvent(QResizeEvent * event) @@ -360,7 +375,6 @@ QString MainWindow::getWindowStateKey() return QString::number(currentView)+"_windowstate_" + UASManager::instance()->getActiveUAS()->getAutopilotTypeName(); } else - return QString::number(currentView)+"_windowstate"; } @@ -514,6 +528,7 @@ void MainWindow::buildCommonWidgets() createDockWidget(simView,new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",VIEW_SIMULATION,Qt::LeftDockWidgetArea); createDockWidget(plannerView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_MISSION,Qt::LeftDockWidgetArea); + createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea); { //createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea); @@ -537,10 +552,17 @@ void MainWindow::buildCommonWidgets() connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); } { - QAction* tempAction = ui.menuTools->addAction(tr("Communication Console")); - menuToDockNameMap[tempAction] = "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET"; - tempAction->setCheckable(true); - connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); + if (!debugConsole) + { + debugConsole = new DebugConsole(); + debugConsole->setWindowTitle("Communications Console"); + debugConsole->hide(); + QAction* tempAction = ui.menuTools->addAction(tr("Communication Console")); + //menuToDockNameMap[tempAction] = "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET"; + tempAction->setCheckable(true); + connect(tempAction,SIGNAL(triggered(bool)),debugConsole,SLOT(setShown(bool))); + + } } createDockWidget(simView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea); @@ -564,16 +586,42 @@ void MainWindow::buildCommonWidgets() connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); } + // createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5); + createDockWidget(simView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5); + + //createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); +// createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8); + //createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + + //UASQuickView *quickview = new UASQuickView(this); + //quickview->addSource(mavlinkDecoder); - createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5); - createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); - createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8); - createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); - createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); - pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North); - pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]); + //createDockWidget(pilotView,quickview,tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + createDockWidget(pilotView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8); + QGCTabbedInfoView *infoview = new QGCTabbedInfoView(this); + infoview->addSource(mavlinkDecoder); + createDockWidget(pilotView,infoview,tr("Info View"),"UAS_INFO_INFOVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + + + //createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8); + +// createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); +// createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); +// pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North); +// pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]); + + //UASRawStatusView *view = new UASRawStatusView(); + //view->setDecoder(mavlinkDecoder); + //view->show(); + //hddisplay->addSource(mavlinkDecoder); + //createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); + //pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North); + //pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]); + + + //createDockWidget(pilotView,new UASActionsWidget(this),tr("Actions"),"UNMANNED_SYSTEM_ACTION_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); // Custom widgets, added last to all menus and layouts buildCustomWidget(); @@ -721,7 +769,12 @@ void MainWindow::loadDockWidget(QString name) { return; } - if (name == "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET") + if (name.startsWith("HIL_CONFIG")) + { + //It's a HIL widget. + showHILConfigurationWidget(UASManager::instance()->getActiveUAS()); + } + else if (name == "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET") { createDockWidget(centerStack->currentWidget(),new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",currentView,Qt::LeftDockWidgetArea); } @@ -747,7 +800,9 @@ void MainWindow::loadDockWidget(QString name) } else if (name == "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET") { - createDockWidget(centerStack->currentWidget(),new DebugConsole(this),tr("Communication Console"),"COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET",currentView,Qt::BottomDockWidgetArea); + //This is now a permanently detached window. + //centralWidgetToDockWidgetsMap[currentView][name] = console; + //createDockWidget(centerStack->currentWidget(),new DebugConsole(this),tr("Communication Console"),"COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET",currentView,Qt::BottomDockWidgetArea); } else if (name == "HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET") { @@ -778,9 +833,10 @@ void MainWindow::loadDockWidget(QString name) qDebug() << "Error loading window:" << name << "Unknown window type"; //createDockWidget(centerStack->currentWidget(),hddisplay,tr("Actuator Status"),"HEADS_DOWN_DISPLAY_2_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); } - else if (name == "HEAD_UP_DISPLAY_DOCKWIDGET") + else if (name == "PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET") { - createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); + // createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); + createDockWidget(centerStack->currentWidget(),new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); } else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET") { @@ -877,8 +933,11 @@ void MainWindow::showHILConfigurationWidget(UASInterface* uas) if (mav && !hilDocks.contains(mav->getUASID())) { + //QGCToolWidget* tool = new QGCToolWidget("Unnamed Tool " + QString::number(ui.menuTools->actions().size())); + //createDockWidget(centerStack->currentWidget(),tool,"Unnamed Tool " + QString::number(ui.menuTools->actions().size()),"UNNAMED_TOOL_" + QString::number(ui.menuTools->actions().size())+"DOCK",currentView,Qt::BottomDockWidgetArea); + QGCHilConfiguration* hconf = new QGCHilConfiguration(mav, this); - QString hilDockName = tr("HIL Config %1").arg(uas->getUASName()); + QString hilDockName = tr("HIL Config %1").arg(uas->getUASName()); QDockWidget* hilDock = createDockWidget(simView, hconf,hilDockName, hilDockName.toUpper().replace(" ", "_"),VIEW_SIMULATION,Qt::LeftDockWidgetArea); hilDocks.insert(mav->getUASID(), hilDock); @@ -892,8 +951,8 @@ void MainWindow::showHILConfigurationWidget(UASInterface* uas) void MainWindow::closeEvent(QCloseEvent *event) { if (isVisible()) storeViewState(); - storeSettings(); aboutToCloseFlag = true; + storeSettings(); mavlink->storeSettings(); UASManager::instance()->storeSettings(); QMainWindow::closeEvent(event); @@ -1539,6 +1598,8 @@ void MainWindow::addLink(LinkInterface *link) if (!found) { // || udp CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); + commsWidgetList.append(commWidget); + connect(commWidget,SIGNAL(destroyed(QObject*)),this,SLOT(commsWidgetDestroyed(QObject*))); QAction* action = commWidget->getAction(); ui.menuNetwork->addAction(action); @@ -1552,6 +1613,13 @@ void MainWindow::addLink(LinkInterface *link) } } } +void MainWindow::commsWidgetDestroyed(QObject *obj) +{ + if (commsWidgetList.contains(obj)) + { + commsWidgetList.removeOne(obj); + } +} void MainWindow::setActiveUAS(UASInterface* uas) { diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 3b5a63562852aa57ee3b3078b336f4b6b6cacf38..eaffba3e32cc3d0263d40fd2a5cdc99e1d92bd63 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -278,6 +278,8 @@ public slots: /** @brief Update the window name */ void configureWindowName(); + void commsWidgetDestroyed(QObject *obj); + signals: void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE newTheme); void initStatusChanged(const QString& message, int alignment, const QColor &color); @@ -424,6 +426,8 @@ protected: QPointer toolBar; QPointer customStatusBar; + QPointer debugConsole; + QPointer mavlinkInspectorWidget; QPointer mavlinkDecoder; QPointer mavlinkSenderWidget; @@ -469,6 +473,7 @@ protected: QTimer windowNameUpdateTimer; private: + QList commsWidgetList; QMap customWidgetNameToFilenameMap; QMap menuToDockNameMap; QMap dockToTitleBarMap; diff --git a/src/ui/PrimaryFlightDisplay.cpp b/src/ui/PrimaryFlightDisplay.cpp new file mode 100644 index 0000000000000000000000000000000000000000..b5a732bf37b0dc2c78fea88b089dc5263895a2dc --- /dev/null +++ b/src/ui/PrimaryFlightDisplay.cpp @@ -0,0 +1,1580 @@ +#include "PrimaryFlightDisplay.h" +#include "UASManager.h" + +//#include "ui_primaryflightdisplay.h" +#include +#include +#include +#include +#include +#include +#include +#include +//#include + +#define SEPARATE_COMPASS_ASPECTRATIO (3.0f/4.0f) + +#define LINEWIDTH 0.0036f + +//#define TAPES_TEXT_SIZE 0.028 +//#define AI_TEXT_SIZE 0.040 +//#define AI_TEXT_MIN_PIXELS 12 +//#define AI_TEXT_MAX_PIXELS 36 +//#define PANELS_TEXT_SIZE 0.030 +//#define COMPASS_SCALE_TEXT_SIZE 0.16 + +#define SMALL_TEXT_SIZE 0.03f +#define MEDIUM_TEXT_SIZE (SMALL_TEXT_SIZE*1.2f) +#define LARGE_TEXT_SIZE (MEDIUM_TEXT_SIZE*1.2f) + +#define SHOW_ZERO_ON_SCALES true + +// all in units of display height +#define ROLL_SCALE_RADIUS 0.42f +#define ROLL_SCALE_TICKMARKLENGTH 0.04f +#define ROLL_SCALE_MARKERWIDTH 0.06f +#define ROLL_SCALE_MARKERHEIGHT 0.04f +// scale max. degrees +#define ROLL_SCALE_RANGE 60 + +// fraction of height to translate for each degree of pitch. +#define PITCHTRANSLATION 65.0 +// 10 degrees for each line +#define PITCH_SCALE_RESOLUTION 5 +#define PITCH_SCALE_MAJORWIDTH 0.1 +#define PITCH_SCALE_MINORWIDTH 0.066 + +// Beginning from PITCH_SCALE_WIDTHREDUCTION_FROM degrees of +/- pitch, the +// width of the lines is reduced, down to PITCH_SCALE_WIDTHREDUCTION times +// the normal width. This helps keep orientation in extreme attitudes. +#define PITCH_SCALE_WIDTHREDUCTION_FROM 30 +#define PITCH_SCALE_WIDTHREDUCTION 0.3 + +#define PITCH_SCALE_HALFRANGE 15 + +// The number of degrees to either side of the heading to draw the compass disk. +// 180 is valid, this will draw a complete disk. If the disk is partly clipped +// away, less will do. + +#define COMPASS_DISK_MAJORTICK 10 +#define COMPASS_DISK_ARROWTICK 45 +#define COMPASS_DISK_MAJORLINEWIDTH 0.006 +#define COMPASS_DISK_MINORLINEWIDTH 0.004 +#define COMPASS_DISK_RESOLUTION 10 +#define COMPASS_SEPARATE_DISK_RESOLUTION 5 +#define COMPASS_DISK_MARKERWIDTH 0.2 +#define COMPASS_DISK_MARKERHEIGHT 0.133 + +#define CROSSTRACK_MAX 1000 +#define CROSSTRACK_RADIUS 0.6 + +#define TAPE_GAUGES_TICKWIDTH_MAJOR 0.25 +#define TAPE_GAUGES_TICKWIDTH_MINOR 0.15 + +// The altitude difference between top and bottom of scale +#define ALTIMETER_LINEAR_SPAN 50 +// every 5 meters there is a tick mark +#define ALTIMETER_LINEAR_RESOLUTION 5 +// every 10 meters there is a number +#define ALTIMETER_LINEAR_MAJOR_RESOLUTION 10 + +// Projected: An experiment. Make tape appear projected from a cylinder, like a French "drum" style gauge. +// The altitude difference between top and bottom of scale +#define ALTIMETER_PROJECTED_SPAN 50 +// every 5 meters there is a tick mark +#define ALTIMETER_PROJECTED_RESOLUTION 5 +// every 10 meters there is a number +#define ALTIMETER_PROJECTED_MAJOR_RESOLUTION 10 +// min. and max. vertical velocity +//#define ALTIMETER_PROJECTED + +// min. and max. vertical velocity +#define ALTIMETER_VVI_SPAN 5 +#define ALTIMETER_VVI_WIDTH 0.2 + +// Now the same thing for airspeed! +#define AIRSPEED_LINEAR_SPAN 15 +#define AIRSPEED_LINEAR_RESOLUTION 1 +#define AIRSPEED_LINEAR_MAJOR_RESOLUTION 5 + +#define UNKNOWN_BATTERY -1 +#define UNKNOWN_ATTITUDE 0 +#define UNKNOWN_ALTITUDE -1000 +#define UNKNOWN_SPEED -1 +#define UNKNOWN_COUNT -1 +#define UNKNOWN_GPSFIXTYPE -1 + +/* + *@TODO: + * global fixed pens (and painters too?) + * repaint on demand multiple canvases + * multi implementation with shared model class + */ +double PrimaryFlightDisplay_round(double value, int digits=0) +{ + return floor(value * pow(10, digits) + 0.5) / pow(10, digits); +} + +const int PrimaryFlightDisplay::tickValues[] = {10, 20, 30, 45, 60}; +const QString PrimaryFlightDisplay::compassWindNames[] = { + QString("N"), + QString("NE"), + QString("E"), + QString("SE"), + QString("S"), + QString("SW"), + QString("W"), + QString("NW") +}; + +PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *parent) : + QWidget(parent), + + uas(NULL), + + altimeterMode(GPS_MAIN), + altimeterFrame(ASL), + speedMode(GROUND_MAIN), + + roll(UNKNOWN_ATTITUDE), + pitch(UNKNOWN_ATTITUDE), + // heading(NAN), + heading(UNKNOWN_ATTITUDE), + primaryAltitude(UNKNOWN_ALTITUDE), + GPSAltitude(UNKNOWN_ALTITUDE), + aboveHomeAltitude(UNKNOWN_ALTITUDE), + primarySpeed(UNKNOWN_SPEED), + groundspeed(UNKNOWN_SPEED), + verticalVelocity(UNKNOWN_ALTITUDE), + + font("Bitstream Vera Sans"), + refreshTimer(new QTimer(this)), + + navigationCrosstrackError(0), + navigationTargetBearing(UNKNOWN_ATTITUDE), + + layout(COMPASS_INTEGRATED), + style(OVERLAY_HSI), + + redColor(QColor::fromHsvF(0, 0.75, 0.9)), + amberColor(QColor::fromHsvF(0.12, 0.6, 1.0)), + greenColor(QColor::fromHsvF(0.25, 0.8, 0.8)), + + lineWidth(2), + fineLineWidth(1), + + instrumentEdgePen(QColor::fromHsvF(0, 0, 0.65, 0.5)), + // AIEdgePen(QColor::fromHsvF(0, 0, 0.65, 0.5)), + + instrumentBackground(QColor::fromHsvF(0, 0, 0.3, 0.3)), + instrumentOpagueBackground(QColor::fromHsvF(0, 0, 0.3, 1.0)) +{ + setMinimumSize(120, 80); + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + + // Connect with UAS + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); + if (UASManager::instance()->getActiveUAS() != NULL) setActiveUAS(UASManager::instance()->getActiveUAS()); + + // Refresh timer + refreshTimer->setInterval(updateInterval); + // connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD())); + connect(refreshTimer, SIGNAL(timeout()), this, SLOT(update())); +} + +PrimaryFlightDisplay::~PrimaryFlightDisplay() +{ + refreshTimer->stop(); +} + + +QSize PrimaryFlightDisplay::sizeHint() const +{ + return QSize(width(), (width()*3.0f)/4); +} + +void PrimaryFlightDisplay::showEvent(QShowEvent* event) +{ + // React only to internal (pre-display) + // events + QWidget::showEvent(event); + refreshTimer->start(updateInterval); + emit visibilityChanged(true); +} + +void PrimaryFlightDisplay::hideEvent(QHideEvent* event) +{ + // React only to internal (pre-display) + // events + refreshTimer->stop(); + QWidget::hideEvent(event); + emit visibilityChanged(false); +} + +qreal constrain(qreal value, qreal min, qreal max) { + if (valuemax) value=max; + return value; +} + +void PrimaryFlightDisplay::resizeEvent(QResizeEvent *e) { + QWidget::resizeEvent(e); + + qreal size = e->size().width(); + //if(e->size().height()size().height(); + + lineWidth = constrain(size*LINEWIDTH, 1, 6); + fineLineWidth = constrain(size*LINEWIDTH*2/3, 1, 2); + + instrumentEdgePen.setWidthF(fineLineWidth); + //AIEdgePen.setWidthF(fineLineWidth); + + smallTestSize = size * SMALL_TEXT_SIZE; + mediumTextSize = size * MEDIUM_TEXT_SIZE; + largeTextSize = size * LARGE_TEXT_SIZE; + + /* + * Try without layout Change-O-Matic. It was too complicated. + qreal aspect = e->size().width() / e->size().height(); + if (aspect <= SEPARATE_COMPASS_ASPECTRATIO) + layout = COMPASS_SEPARATED; + else + layout = COMPASS_INTEGRATED; + */ + // qDebug("Width %d height %d decision %d", e->size().width(), e->size().height(), layout); +} + +void PrimaryFlightDisplay::paintEvent(QPaintEvent *event) +{ + // Event is not needed + // the event is ignored as this widget + // is refreshed automatically + Q_UNUSED(event); + //makeDummyData(); + doPaint(); +} + +/* + * Interface towards qgroundcontrol + */ +/** + * + * @param uas the UAS/MAV to monitor/display with the HUD + */ +void PrimaryFlightDisplay::setActiveUAS(UASInterface* uas) +{ + if (this->uas != NULL) { + // Disconnect any previously connected active MAV + disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); + disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); + disconnect(this->uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int))); + disconnect(this->uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64))); + disconnect(this->uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSSpeed(UASInterface*,double,quint64))); + disconnect(this->uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, SLOT(updateClimbRate(UASInterface*, AltitudeMeasurementSource, double, quint64))); + disconnect(this->uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64))); + disconnect(this->uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSAltitude(UASInterface*, double, quint64))); + disconnect(this->uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double))); + + //disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int))); + //disconnect(this->uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString))); + //disconnect(this->uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); + //disconnect(this->uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*))); + //disconnect(this->uas, SIGNAL(armingChanged(bool)), this, SLOT(updateArmed(bool))); + //disconnect(this->uas, SIGNAL(satelliteCountChanged(double, QString)), this, SLOT(updateSatelliteCount(double, QString))); + //disconnect(this->uas, SIGNAL(localizationChanged(UASInterface* uas, int fix)), this, SLOT(updateGPSFixType(UASInterface*,int))); + } + + if (uas) { + // Now connect the new UAS + // Setup communication + connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); + connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); + + //connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, double, int))); + //connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString))); + //connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); + //connect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*))); + //connect(uas, SIGNAL(armingChanged(bool)), this, SLOT(updateArmed(bool))); + //connect(uas, SIGNAL(satelliteCountChanged(double, QString)), this, SLOT(updateSatelliteCount(double, QString))); + + //connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); + //connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int))); + connect(uas, SIGNAL(primarySpeedChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimarySpeed(UASInterface*,double,quint64))); + connect(uas, SIGNAL(gpsSpeedChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSSpeed(UASInterface*,double,quint64))); + connect(uas, SIGNAL(climbRateChanged(UASInterface*, double, quint64)), this, SLOT(updateClimbRate(UASInterface*, AltitudeMeasurementSource, double, quint64))); + connect(uas, SIGNAL(primaryAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updatePrimaryAltitude(UASInterface*, double, quint64))); + connect(uas, SIGNAL(gpsAltitudeChanged(UASInterface*, double, quint64)), this, SLOT(updateGPSAltitude(UASInterface*, double, quint64))); + connect(uas, SIGNAL(navigationControllerErrorsChanged(UASInterface*, double, double, double)), this, SLOT(updateNavigationControllerErrors(UASInterface*, double, double, double))); + + // Set new UAS + this->uas = uas; + } +} + +void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp) +{ + Q_UNUSED(uas); + Q_UNUSED(timestamp); + if (!isnan(roll) && !isinf(roll) && !isnan(pitch) && !isinf(pitch) && !isnan(yaw) && !isinf(yaw)) + { + // TODO: Units conversion? // Called from UAS.cc l. 646 + this->roll = roll * (180.0 / M_PI); + this->pitch = pitch * (180.0 / M_PI); + yaw = yaw * (180.0 / M_PI); + if (yaw<0) yaw+=360; + this->heading = yaw; + } + // TODO: Else-part. We really should have an "attitude bad or unknown" indication instead of just freezing. + + //qDebug("r,p,y: %f,%f,%f", roll, pitch, yaw); +} + +/* + * TODO! Implementation or removal of this. + * Currently a dummy. + */ +void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp) +{ + Q_UNUSED(uas); + Q_UNUSED(component); + Q_UNUSED(timestamp); + // Called from UAS.cc l. 616 + if (!isnan(roll) && !isinf(roll) && !isnan(pitch) && !isinf(pitch) && !isnan(yaw) && !isinf(yaw)) { + this->roll = roll * (180.0 / M_PI); + this->pitch = pitch * (180.0 / M_PI); + yaw = yaw * (180.0 / M_PI); + if (yaw<0) yaw+=360; + this->heading = yaw; + } + // qDebug("(2) r,p,y: %f,%f,%f", roll, pitch, yaw); + +} + +/* + * TODO! Examine what data comes with this call, should we consider it airspeed, ground speed or + * should we not consider it at all? + */ +void PrimaryFlightDisplay::updatePrimarySpeed(UASInterface* uas, double speed, quint64 timestamp) +{ + Q_UNUSED(uas); + Q_UNUSED(timestamp); + + primarySpeed = speed; + didReceivePrimarySpeed = true; +} + +void PrimaryFlightDisplay::updateGPSSpeed(UASInterface* uas, double speed, quint64 timestamp) +{ + Q_UNUSED(uas); + Q_UNUSED(timestamp); + + groundspeed = speed; + if (!didReceivePrimarySpeed) + primarySpeed = speed; +} + +void PrimaryFlightDisplay::updateClimbRate(UASInterface* uas, double climbRate, quint64 timestamp) { + Q_UNUSED(uas); + Q_UNUSED(timestamp); + verticalVelocity = climbRate; +} + +void PrimaryFlightDisplay::updatePrimaryAltitude(UASInterface* uas, double altitude, quint64 timestamp) { + Q_UNUSED(uas); + Q_UNUSED(timestamp); + primaryAltitude = altitude; + didReceivePrimaryAltitude = true; +} + +void PrimaryFlightDisplay::updateGPSAltitude(UASInterface* uas, double altitude, quint64 timestamp) { + Q_UNUSED(uas); + Q_UNUSED(timestamp); + GPSAltitude = altitude; + if (!didReceivePrimaryAltitude) + primaryAltitude = altitude; +} + +void PrimaryFlightDisplay::updateNavigationControllerErrors(UASInterface* uas, double altitudeError, double speedError, double xtrackError) { + Q_UNUSED(uas); + this->navigationAltitudeError = altitudeError; + this->navigationSpeedError = speedError; + this->navigationCrosstrackError = xtrackError; +} + + +/* + * Private and such + */ + +// TODO: Move to UAS. Real working implementation. +bool PrimaryFlightDisplay::isAirplane() { + if (!this->uas) + return false; + switch(this->uas->getSystemType()) { + case MAV_TYPE_GENERIC: + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_AIRSHIP: + case MAV_TYPE_FLAPPING_WING: + return true; + default: + return false; + } +} + +// TODO: Implement. Should return true when navigating. +// That would be (APM) in AUTO and RTL modes. +// This could forward to a virtual on UAS bool isNavigatingAutonomusly() or whatever. +bool PrimaryFlightDisplay::shouldDisplayNavigationData() { + return true; +} + +void PrimaryFlightDisplay::drawTextCenter ( + QPainter& painter, + QString text, + float pixelSize, + float x, + float y) +{ + font.setPixelSize(pixelSize); + painter.setFont(font); + + QFontMetrics metrics = QFontMetrics(font); + QRect bounds = metrics.boundingRect(text); + int flags = Qt::AlignCenter | Qt::TextDontClip; // For some reason the bounds rect is too small! + painter.drawText(x /*+bounds.x()*/ -bounds.width()/2, y /*+bounds.y()*/ -bounds.height()/2, bounds.width(), bounds.height(), flags, text); +} + +void PrimaryFlightDisplay::drawTextLeftCenter ( + QPainter& painter, + QString text, + float pixelSize, + float x, + float y) +{ + font.setPixelSize(pixelSize); + painter.setFont(font); + + QFontMetrics metrics = QFontMetrics(font); + QRect bounds = metrics.boundingRect(text); + int flags = Qt::AlignLeft | Qt::TextDontClip; // For some reason the bounds rect is too small! + painter.drawText(x /*+bounds.x()*/, y /*+bounds.y()*/ -bounds.height()/2, bounds.width(), bounds.height(), flags, text); +} + +void PrimaryFlightDisplay::drawTextRightCenter ( + QPainter& painter, + QString text, + float pixelSize, + float x, + float y) +{ + font.setPixelSize(pixelSize); + painter.setFont(font); + + QFontMetrics metrics = QFontMetrics(font); + QRect bounds = metrics.boundingRect(text); + int flags = Qt::AlignRight | Qt::TextDontClip; // For some reason the bounds rect is too small! + painter.drawText(x /*+bounds.x()*/ -bounds.width(), y /*+bounds.y()*/ -bounds.height()/2, bounds.width(), bounds.height(), flags, text); +} + +void PrimaryFlightDisplay::drawTextCenterTop ( + QPainter& painter, + QString text, + float pixelSize, + float x, + float y) +{ + font.setPixelSize(pixelSize); + painter.setFont(font); + + QFontMetrics metrics = QFontMetrics(font); + QRect bounds = metrics.boundingRect(text); + int flags = Qt::AlignCenter | Qt::TextDontClip; // For some reason the bounds rect is too small! + painter.drawText(x /*+bounds.x()*/ -bounds.width()/2, y+bounds.height() /*+bounds.y()*/, bounds.width(), bounds.height(), flags, text); +} + +void PrimaryFlightDisplay::drawTextCenterBottom ( + QPainter& painter, + QString text, + float pixelSize, + float x, + float y) +{ + font.setPixelSize(pixelSize); + painter.setFont(font); + + QFontMetrics metrics = QFontMetrics(font); + QRect bounds = metrics.boundingRect(text); + int flags = Qt::AlignCenter; + painter.drawText(x /*+bounds.x()*/ -bounds.width()/2, y /*+bounds.y()*/, bounds.width(), bounds.height(), flags, text); +} + +void PrimaryFlightDisplay::drawInstrumentBackground(QPainter& painter, QRectF edge) { + painter.setPen(instrumentEdgePen); + painter.drawRect(edge); +} + +void PrimaryFlightDisplay::fillInstrumentBackground(QPainter& painter, QRectF edge) { + painter.setPen(instrumentEdgePen); + painter.setBrush(instrumentBackground); + painter.drawRect(edge); + painter.setBrush(Qt::NoBrush); +} + +void PrimaryFlightDisplay::fillInstrumentOpagueBackground(QPainter& painter, QRectF edge) { + painter.setPen(instrumentEdgePen); + painter.setBrush(instrumentOpagueBackground); + painter.drawRect(edge); + painter.setBrush(Qt::NoBrush); +} + +qreal pitchAngleToTranslation(qreal viewHeight, float pitch) { + return pitch * viewHeight / PITCHTRANSLATION; +} + +void PrimaryFlightDisplay::drawAIAirframeFixedFeatures(QPainter& painter, QRectF area) { + // red line from -7/10 to -5/10 half-width + // red line from 7/10 to 5/10 half-width + // red slanted line from -2/10 half-width to 0 + // red slanted line from 2/10 half-width to 0 + // red arrow thing under roll scale + // prepareTransform(painter, width, height); + painter.resetTransform(); + painter.translate(area.center()); + + qreal w = area.width(); + qreal h = area.height(); + + QPen pen; + pen.setWidthF(lineWidth * 1.5); + pen.setColor(redColor); + painter.setPen(pen); + + float length = 0.15; + float side = 0.5; + // The 2 lines at sides. + painter.drawLine(QPointF(-side*w, 0), QPointF(-(side-length)*w, 0)); + painter.drawLine(QPointF(side*w, 0), QPointF((side-length)*w, 0)); + + float rel = length/qSqrt(2); + // The gull + painter.drawLine(QPointF(rel*w, rel*w/2), QPoint(0, 0)); + painter.drawLine(QPointF(-rel*w, rel*w/2), QPoint(0, 0)); + + // The roll scale marker. + QPainterPath markerPath(QPointF(0, -w*ROLL_SCALE_RADIUS+1)); + markerPath.lineTo(-h*ROLL_SCALE_MARKERWIDTH/2, -w*(ROLL_SCALE_RADIUS-ROLL_SCALE_MARKERHEIGHT)+1); + markerPath.lineTo(h*ROLL_SCALE_MARKERWIDTH/2, -w*(ROLL_SCALE_RADIUS-ROLL_SCALE_MARKERHEIGHT)+1); + markerPath.closeSubpath(); + painter.drawPath(markerPath); +} + +inline qreal min4(qreal a, qreal b, qreal c, qreal d) { + if(ba) a=b; + if(c>a) a=c; + if(d>a) a=d; + return a; +} + +void PrimaryFlightDisplay::drawAIGlobalFeatures( + QPainter& painter, + QRectF mainArea, + QRectF paintArea) { + + painter.resetTransform(); + painter.translate(mainArea.center()); + + qreal pitchPixels = pitchAngleToTranslation(mainArea.height(), pitch); + qreal gradientEnd = pitchAngleToTranslation(mainArea.height(), 60); + + //painter.rotate(-roll); + //painter.translate(0, pitchPixels); + + // QTransform forwardTransform; + //forwardTransform.translate(mainArea.center().x(), mainArea.center().y()); + painter.rotate(-roll); + painter.translate(0, pitchPixels); + + // Calculate the radius of area we need to paint to cover all. + QTransform rtx = painter.transform().inverted(); + + QPointF topLeft = rtx.map(paintArea.topLeft()); + QPointF topRight = rtx.map(paintArea.topRight()); + QPointF bottomLeft = rtx.map(paintArea.bottomLeft()); + QPointF bottomRight = rtx.map(paintArea.bottomRight()); + // Just KISS... make a rectangluar basis. + qreal minx = min4(topLeft.x(), topRight.x(), bottomLeft.x(), bottomRight.x()); + qreal maxx = max4(topLeft.x(), topRight.x(), bottomLeft.x(), bottomRight.x()); + qreal miny = min4(topLeft.y(), topRight.y(), bottomLeft.y(), bottomRight.y()); + qreal maxy = max4(topLeft.y(), topRight.y(), bottomLeft.y(), bottomRight.y()); + + QPointF hzonLeft = QPoint(minx, 0); + QPointF hzonRight = QPoint(maxx, 0); + + QPainterPath skyPath(hzonLeft); + skyPath.lineTo(QPointF(minx, miny)); + skyPath.lineTo(QPointF(maxx, miny)); + skyPath.lineTo(hzonRight); + skyPath.closeSubpath(); + + // TODO: The gradient is wrong now. + QLinearGradient skyGradient(0, -gradientEnd, 0, 0); + skyGradient.setColorAt(0, QColor::fromHsvF(0.6, 1.0, 0.7)); + skyGradient.setColorAt(1, QColor::fromHsvF(0.6, 0.25, 0.9)); + QBrush skyBrush(skyGradient); + painter.fillPath(skyPath, skyBrush); + + QPainterPath groundPath(hzonRight); + groundPath.lineTo(maxx, maxy); + groundPath.lineTo(minx, maxy); + groundPath.lineTo(hzonLeft); + groundPath.closeSubpath(); + + QLinearGradient groundGradient(0, gradientEnd, 0, 0); + groundGradient.setColorAt(0, QColor::fromHsvF(0.25, 1, 0.5)); + groundGradient.setColorAt(1, QColor::fromHsvF(0.25, 0.25, 0.5)); + QBrush groundBrush(groundGradient); + painter.fillPath(groundPath, groundBrush); + + QPen pen; + pen.setWidthF(lineWidth); + pen.setColor(greenColor); + painter.setPen(pen); + + QPointF start(-mainArea.width(), 0); + QPoint end(mainArea.width(), 0); + painter.drawLine(start, end); +} + +void PrimaryFlightDisplay::drawPitchScale( + QPainter& painter, + QRectF area, + float intrusion, + bool drawNumbersLeft, + bool drawNumbersRight + ) { + + // The area should be quadratic but if not width is the major size. + qreal w = area.width(); + if (w PITCH_SCALE_WIDTHREDUCTION_FROM) { + // we want: 1 at PITCH_SCALE_WIDTHREDUCTION_FROM and PITCH_SCALE_WIDTHREDUCTION at 90. + // That is PITCH_SCALE_WIDTHREDUCTION + (1-PITCH_SCALE_WIDTHREDUCTION) * f(pitch) + // where f(90)=0 and f(PITCH_SCALE_WIDTHREDUCTION_FROM)=1 + // f(p) = (90-p) * 1/(90-PITCH_SCALE_WIDTHREDUCTION_FROM) + // or PITCH_SCALE_WIDTHREDUCTION + f(pitch) - f(pitch) * PITCH_SCALE_WIDTHREDUCTION + // or PITCH_SCALE_WIDTHREDUCTION (1-f(pitch)) + f(pitch) + int fromVertical = abs(pitch>=0 ? 90-pitch : -90-pitch); + float temp = fromVertical * 1/(90.0f-PITCH_SCALE_WIDTHREDUCTION_FROM); + linewidth *= (PITCH_SCALE_WIDTHREDUCTION * (1-temp) + temp); + } + + float shift = pitchAngleToTranslation(w, pitch-degrees); + + // TODO: Intrusion detection and evasion. That is, don't draw + // where the compass has intruded. + + painter.translate(0, shift); + QPointF start(-linewidth*w, 0); + QPointF end(linewidth*w, 0); + painter.drawLine(start, end); + + if (isMajor && (drawNumbersLeft||drawNumbersRight)) { + int displayDegrees = degrees; + if(displayDegrees>90) displayDegrees = 180-displayDegrees; + else if (displayDegrees<-90) displayDegrees = -180 - displayDegrees; + if (SHOW_ZERO_ON_SCALES || degrees) { + QString s_number; //= QString("%d").arg(degrees); + s_number.sprintf("%d", displayDegrees); + if (drawNumbersLeft) drawTextRightCenter(painter, s_number, mediumTextSize, -PITCH_SCALE_MAJORWIDTH * w-10, 0); + if (drawNumbersRight) drawTextLeftCenter(painter, s_number, mediumTextSize, PITCH_SCALE_MAJORWIDTH * w+10, 0); + } + } + + painter.setTransform(savedTransform); + } +} + +void PrimaryFlightDisplay::drawRollScale( + QPainter& painter, + QRectF area, + bool drawTicks, + bool drawNumbers) { + + qreal w = area.width(); + if (wlength) ?-tickValues[i-length-1] : tickValues[i]; + //degrees = 180 - degrees; + painter.rotate(degrees - previousRotation); + previousRotation = degrees; + + QPointF start(0, -_size/2); + QPointF end(0, -(1.0+ROLL_SCALE_TICKMARKLENGTH)*_size/2); + + painter.drawLine(start, end); + + QString s_number; //= QString("%d").arg(degrees); + if (SHOW_ZERO_ON_SCALES || degrees) + s_number.sprintf("%d", abs(degrees)); + + if (drawNumbers) { + drawTextCenterBottom(painter, s_number, mediumTextSize, 0, -(ROLL_SCALE_RADIUS+ROLL_SCALE_TICKMARKLENGTH*1.7)*w); + } + } + } +} + +void PrimaryFlightDisplay::drawAIAttitudeScales( + QPainter& painter, + QRectF area, + float intrusion + ) { + // To save computations, we do these transformations once for both scales: + painter.resetTransform(); + painter.translate(area.center()); + painter.rotate(-roll); + QTransform saved = painter.transform(); + + drawRollScale(painter, area, true, true); + painter.setTransform(saved); + drawPitchScale(painter, area, intrusion, true, true); +} + +void PrimaryFlightDisplay::drawAICompassDisk(QPainter& painter, QRectF area, float halfspan) { + float start = heading - halfspan; + float end = heading + halfspan; + + int firstTick = ceil(start / COMPASS_DISK_RESOLUTION) * COMPASS_DISK_RESOLUTION; + int lastTick = floor(end / COMPASS_DISK_RESOLUTION) * COMPASS_DISK_RESOLUTION; + + float radius = area.width()/2; + float innerRadius = radius * 0.96; + painter.resetTransform(); + painter.setBrush(instrumentBackground); + painter.setPen(instrumentEdgePen); + painter.drawEllipse(area); + painter.setBrush(Qt::NoBrush); + + QPen scalePen(Qt::black); + scalePen.setWidthF(fineLineWidth); + + for (int tickYaw = firstTick; tickYaw <= lastTick; tickYaw += COMPASS_DISK_RESOLUTION) { + int displayTick = tickYaw; + if (displayTick < 0) displayTick+=360; + else if (displayTick>=360) displayTick-=360; + + // yaw is in center. + float off = tickYaw - heading; + // wrap that to ]-180..180] + if (off<=-180) off+= 360; else if (off>180) off -= 360; + + painter.translate(area.center()); + painter.rotate(off); + bool drewArrow = false; + bool isMajor = displayTick % COMPASS_DISK_MAJORTICK == 0; + + if (displayTick==30 || displayTick==60 || + displayTick==120 || displayTick==150 || + displayTick==210 || displayTick==240 || + displayTick==300 || displayTick==330) { + // draw a number + QString s_number; + s_number.sprintf("%d", displayTick/10); + painter.setPen(scalePen); + drawTextCenter(painter, s_number, /*COMPASS_SCALE_TEXT_SIZE*radius*/ smallTestSize, 0, -innerRadius*0.75); + } else { + if (displayTick % COMPASS_DISK_ARROWTICK == 0) { + if (displayTick!=0) { + QPainterPath markerPath(QPointF(0, -innerRadius*(1-COMPASS_DISK_MARKERHEIGHT/2))); + markerPath.lineTo(innerRadius*COMPASS_DISK_MARKERWIDTH/4, -innerRadius); + markerPath.lineTo(-innerRadius*COMPASS_DISK_MARKERWIDTH/4, -innerRadius); + markerPath.closeSubpath(); + painter.setPen(scalePen); + painter.setBrush(Qt::SolidPattern); + painter.drawPath(markerPath); + painter.setBrush(Qt::NoBrush); + drewArrow = true; + } + if (displayTick%90 == 0) { + // Also draw a label + QString name = compassWindNames[displayTick / 45]; + painter.setPen(scalePen); + drawTextCenter(painter, name, mediumTextSize, 0, -innerRadius*0.75); + } + } + } + // draw the scale lines. If an arrow was drawn, stay off from it. + + QPointF p_start = drewArrow ? QPoint(0, -innerRadius*0.94) : QPoint(0, -innerRadius); + QPoint p_end = isMajor ? QPoint(0, -innerRadius*0.86) : QPoint(0, -innerRadius*0.90); + + painter.setPen(scalePen); + painter.drawLine(p_start, p_end); + painter.resetTransform(); + } + + painter.setPen(scalePen); + //painter.setBrush(Qt::SolidPattern); + painter.translate(area.center()); + QPainterPath markerPath(QPointF(0, -radius-2)); + markerPath.lineTo(radius*COMPASS_DISK_MARKERWIDTH/2, -radius-radius*COMPASS_DISK_MARKERHEIGHT-2); + markerPath.lineTo(-radius*COMPASS_DISK_MARKERWIDTH/2, -radius-radius*COMPASS_DISK_MARKERHEIGHT-2); + markerPath.closeSubpath(); + painter.drawPath(markerPath); + + qreal digitalCompassYCenter = -radius*0.52; + qreal digitalCompassHeight = radius*0.28; + + QPointF digitalCompassBottom(0, digitalCompassYCenter+digitalCompassHeight); + QPointF digitalCompassAbsoluteBottom = painter.transform().map(digitalCompassBottom); + + qreal digitalCompassUpshift = digitalCompassAbsoluteBottom.y()>height() ? digitalCompassAbsoluteBottom.y()-height() : 0; + + QRectF digitalCompassRect(-radius/3, -radius*0.52-digitalCompassUpshift, radius*2/3, radius*0.28); + painter.setPen(instrumentEdgePen); + painter.drawRoundedRect(digitalCompassRect, instrumentEdgePen.widthF()*2/3, instrumentEdgePen.widthF()*2/3); + + /* final safeguard for really stupid systems */ + int digitalCompassValue = static_cast(qRound((double)heading)) % 360; + + QString s_digitalCompass; + s_digitalCompass.sprintf("%03d", digitalCompassValue); + + QPen pen; + pen.setWidthF(lineWidth); + pen.setColor(Qt::white); + painter.setPen(pen); + + drawTextCenter(painter, s_digitalCompass, largeTextSize, 0, -radius*0.38-digitalCompassUpshift); + +// dummy +// navigationTargetBearing = 10; +// navigationCrosstrackError = 500; + + // The CDI + if (shouldDisplayNavigationData() && navigationTargetBearing != UNKNOWN_ATTITUDE && !isinf(navigationCrosstrackError)) { + painter.resetTransform(); + painter.translate(area.center()); + // TODO : Sign might be wrong? + // TODO : The case where error exceeds max. Truncate to max. and make that visible somehow. + bool errorBeyondRadius = false; + if (abs(navigationCrosstrackError) > CROSSTRACK_MAX) { + errorBeyondRadius = true; + navigationCrosstrackError = navigationCrosstrackError>0 ? CROSSTRACK_MAX : -CROSSTRACK_MAX; + } + + float r = radius * CROSSTRACK_RADIUS; + float x = navigationCrosstrackError / CROSSTRACK_MAX * r; + float y = qSqrt(r*r - x*x); // the positive y, there is also a negative. + + float sillyHeading = 0; + float angle = sillyHeading - navigationTargetBearing; // TODO: sign. + painter.rotate(-angle); + + QPen pen; + pen.setWidthF(lineWidth); + pen.setColor(Qt::black); + painter.setPen(pen); + + painter.drawLine(QPointF(x, y), QPointF(x, -y)); + } +} + +/* +void PrimaryFlightDisplay::drawSeparateCompassDisk(QPainter& painter, QRectF area) { + float radius = area.width()/2; + float innerRadius = radius * 0.96; + painter.resetTransform(); + + painter.setBrush(instrumentOpagueBackground); + painter.setPen(instrumentEdgePen); + painter.drawEllipse(area); + painter.setBrush(Qt::NoBrush); + + QPen scalePen(Qt::white); + scalePen.setWidthF(fineLineWidth); + + for (int displayTick=0; displayTick<360; displayTick+=COMPASS_SEPARATE_DISK_RESOLUTION) { + // yaw is in center. + float off = displayTick - heading; + // wrap that to ]-180..180] + if (off<=-180) off+= 360; else if (off>180) off -= 360; + + painter.translate(area.center()); + painter.rotate(off); + bool drewArrow = false; + bool isMajor = displayTick % COMPASS_DISK_MAJORTICK == 0; + + if (displayTick==30 || displayTick==60 || + displayTick==120 || displayTick==150 || + displayTick==210 || displayTick==240 || + displayTick==300 || displayTick==330) { + // draw a number + QString s_number; + s_number.sprintf("%d", displayTick/10); + painter.setPen(scalePen); + drawTextCenter(painter, s_number, mediumTextSize, 0, -innerRadius*0.75); + } else { + if (displayTick % COMPASS_DISK_ARROWTICK == 0) { + if (displayTick!=0) { + QPainterPath markerPath(QPointF(0, -innerRadius*(1-COMPASS_DISK_MARKERHEIGHT/2))); + markerPath.lineTo(innerRadius*COMPASS_DISK_MARKERWIDTH/4, -innerRadius); + markerPath.lineTo(-innerRadius*COMPASS_DISK_MARKERWIDTH/4, -innerRadius); + markerPath.closeSubpath(); + painter.setPen(scalePen); + painter.setBrush(Qt::SolidPattern); + painter.drawPath(markerPath); + painter.setBrush(Qt::NoBrush); + drewArrow = true; + } + if (displayTick%90 == 0) { + // Also draw a label + QString name = compassWindNames[displayTick / 45]; + painter.setPen(scalePen); + drawTextCenter(painter, name, mediumTextSize, 0, -innerRadius*0.75); + } + } + } + // draw the scale lines. If an arrow was drawn, stay off from it. + + QPointF p_start = drewArrow ? QPoint(0, -innerRadius*0.94) : QPoint(0, -innerRadius); + QPoint p_end = isMajor ? QPoint(0, -innerRadius*0.86) : QPoint(0, -innerRadius*0.90); + + painter.setPen(scalePen); + painter.drawLine(p_start, p_end); + painter.resetTransform(); + } + + painter.setPen(scalePen); + //painter.setBrush(Qt::SolidPattern); + painter.translate(area.center()); + QPainterPath markerPath(QPointF(0, -radius-2)); + markerPath.lineTo(radius*COMPASS_DISK_MARKERWIDTH/2, -radius-radius*COMPASS_DISK_MARKERHEIGHT-2); + markerPath.lineTo(-radius*COMPASS_DISK_MARKERWIDTH/2, -radius-radius*COMPASS_DISK_MARKERHEIGHT-2); + markerPath.closeSubpath(); + painter.drawPath(markerPath); + + QRectF headingNumberRect(-radius/3, radius*0.12, radius*2/3, radius*0.28); + painter.setPen(instrumentEdgePen); + painter.drawRoundedRect(headingNumberRect, instrumentEdgePen.widthF()*2/3, instrumentEdgePen.widthF()*2/3); + + // if (heading < 0) heading += 360; + // else if (heading >= 360) heading -= 360; + int yawCompass = static_cast(heading) % 360; + + QString yawAngle; + yawAngle.sprintf("%03d", yawCompass); + + QPen pen; + pen.setWidthF(lineWidth); + pen.setColor(Qt::white); + painter.setPen(pen); + + drawTextCenter(painter, yawAngle, largeTextSize, 0, radius/4); +} +*/ + +void PrimaryFlightDisplay::drawAltimeter( + QPainter& painter, + QRectF area, // the area where to draw the tape. + float primaryAltitude, + float secondaryAltitude, + float vv + ) { + + painter.resetTransform(); + fillInstrumentBackground(painter, area); + + QPen pen; + pen.setWidthF(lineWidth); + + pen.setColor(Qt::white); + painter.setPen(pen); + + float h = area.height(); + float w = area.width(); + float secondaryAltitudeBoxHeight = mediumTextSize * 2; + // The height where we being with new tickmarks. + float effectiveHalfHeight = h*0.45; + + // not yet implemented: Display of secondary altitude. + // if (isAirplane()) + // effectiveHalfHeight-= secondaryAltitudeBoxHeight; + + float markerHalfHeight = mediumTextSize*0.8; + float leftEdge = instrumentEdgePen.widthF()*2; + float rightEdge = w-leftEdge; + float tickmarkLeft = leftEdge; + float tickmarkRightMajor = tickmarkLeft+TAPE_GAUGES_TICKWIDTH_MAJOR*w; + float tickmarkRightMinor = tickmarkLeft+TAPE_GAUGES_TICKWIDTH_MINOR*w; + float numbersLeft = 0.42*w; + float markerTip = (tickmarkLeft*2+tickmarkRightMajor)/3; + float scaleCenterAltitude = primaryAltitude == UNKNOWN_ALTITUDE ? 0 : primaryAltitude; + + // altitude scale +#ifdef ALTIMETER_PROJECTED + float range = 1.2; + float start = scaleCenterAltitude - ALTIMETER_PROJECTED_SPAN/2; + float end = scaleCenterAltitude + ALTIMETER_PROJECTED_SPAN/2; + int firstTick = ceil(start / ALTIMETER_PROJECTED_RESOLUTION) * ALTIMETER_PROJECTED_RESOLUTION; + int lastTick = floor(end / ALTIMETER_PROJECTED_RESOLUTION) * ALTIMETER_PROJECTED_RESOLUTION; + for (int tickAlt = firstTick; tickAlt <= lastTick; tickAlt += ALTIMETER_PROJECTED_RESOLUTION) { + // a number between 0 and 1. Use as radians directly. + float r = range*(tickAlt-altitude)/(ALTIMETER_PROJECTED_SPAN/2); + float y = effectiveHalfHeight * sin(r); + scale = cos(r); + if (scale<0) scale = -scale; + bool hasText = tickAlt % ALTIMETER_PROJECTED_MAJOR_RESOLUTION == 0; +#else + float start = scaleCenterAltitude - ALTIMETER_LINEAR_SPAN/2; + float end = scaleCenterAltitude + ALTIMETER_LINEAR_SPAN/2; + int firstTick = ceil(start / ALTIMETER_LINEAR_RESOLUTION) * ALTIMETER_LINEAR_RESOLUTION; + int lastTick = floor(end / ALTIMETER_LINEAR_RESOLUTION) * ALTIMETER_LINEAR_RESOLUTION; + for (int tickAlt = firstTick; tickAlt <= lastTick; tickAlt += ALTIMETER_LINEAR_RESOLUTION) { + float y = (tickAlt-scaleCenterAltitude)*effectiveHalfHeight/(ALTIMETER_LINEAR_SPAN/2); + bool isMajor = tickAlt % ALTIMETER_LINEAR_MAJOR_RESOLUTION == 0; +#endif + painter.resetTransform(); + painter.translate(area.left(), area.center().y() - y); + pen.setColor(tickAlt<0 ? redColor : Qt::white); + painter.setPen(pen); + if (isMajor) { + painter.drawLine(tickmarkLeft, 0, tickmarkRightMajor, 0); + QString s_alt; + s_alt.sprintf("%d", abs(tickAlt)); + drawTextLeftCenter(painter, s_alt, mediumTextSize, numbersLeft, 0); + } else { + painter.drawLine(tickmarkLeft, 0, tickmarkRightMinor, 0); + } + } + + QPainterPath markerPath(QPoint(markerTip, 0)); + markerPath.lineTo(markerTip+markerHalfHeight, markerHalfHeight); + markerPath.lineTo(rightEdge, markerHalfHeight); + markerPath.lineTo(rightEdge, -markerHalfHeight); + markerPath.lineTo(markerTip+markerHalfHeight, -markerHalfHeight); + markerPath.closeSubpath(); + + painter.resetTransform(); + painter.translate(area.left(), area.center().y()); + + pen.setWidthF(lineWidth); + pen.setColor(Qt::white); + painter.setPen(pen); + + painter.setBrush(Qt::SolidPattern); + painter.drawPath(markerPath); + painter.setBrush(Qt::NoBrush); + + pen.setColor(Qt::white); + painter.setPen(pen); + + QString s_alt; + if(primaryAltitude == UNKNOWN_ALTITUDE) + s_alt.sprintf("---"); + else + s_alt.sprintf("%3.0f", primaryAltitude); + + float xCenter = (markerTip+rightEdge)/2; + drawTextCenter(painter, s_alt, /* TAPES_TEXT_SIZE*width()*/ mediumTextSize, xCenter, 0); + + if (vv == UNKNOWN_ALTITUDE) return; + float vvPixHeight = -vv/ALTIMETER_VVI_SPAN * effectiveHalfHeight; + if (abs (vvPixHeight)